diff --git a/CMakeLists.txt b/CMakeLists.txt index bf9ed4dd84..64899d8cf6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) @@ -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 @@ -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}" diff --git a/Changelog.md b/Changelog.md index 24d313f289..e55f66392c 100644 --- a/Changelog.md +++ b/Changelog.md @@ -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://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) + +1. Drag and drop meshes into scene + * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + +1. Set protobuf_MODULE_COMPATIBLE before any find_package call + * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + +1. [DiffDrive] add enable/disable + * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + +1. Fix component inspector shutdown crash + * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + +1. Add UserCommands Plugin. + * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + +1. Setting the intiial velocity for a model or joint + * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + +1. Examples and tutorial on using rendering API from plugins + * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + +1. Add missing IGNITION_GAZEBO_VISIBLE macros + * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) + +1. Fix visibility macro names when used by a different component (Windows) + * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + +1. No install apt recommends and clear cache + * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + +1. Add 25percent darker view angle icons + * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + +1. Expose a test fixture helper class + * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + +1. Fix logic to disable server default plugins loading + * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + +1. removed unneeded plugin update + * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + +1. Functions to enable velocity and acceleration checks on Link + * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + +1. Support adding systems that don't come from a plugin + * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + +1. 3D plot GUI plugin + * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) 1. Add a convenience function for getting possibly non-existing components. * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml deleted file mode 100644 index 1e3379a5e3..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-physics5-dev - # libignition-common4-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-common4 - - 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-common4-dev - libignition-math6-eigen3-dev - libignition-plugin-dev - libignition-tools-dev - # libignition-fuel-tools4-dev - # libignition-physics2-dev - # libsdformat12-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/docker/scripts/install_ign_deps.sh b/docker/scripts/install_ign_deps.sh index 18d9ab52f7..63948f5fb6 100755 --- a/docker/scripts/install_ign_deps.sh +++ b/docker/scripts/install_ign_deps.sh @@ -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 diff --git a/examples/standalone/entity_creation/entity_creation.cc b/examples/standalone/entity_creation/entity_creation.cc index 6184f1beef..ff7a2c980e 100644 --- a/examples/standalone/entity_creation/entity_creation.cc +++ b/examples/standalone/entity_creation/entity_creation.cc @@ -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; 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 @@ 1 true logical_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 @@ 30 true altimeter + true @@ -136,6 +137,7 @@ 30 true air_pressure + true 123 @@ -152,12 +154,14 @@ 100 true imu + true 1 100 true magnetometer + 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 @@ 30 true camera_alone + true 10 depth_camera + true 1.05 @@ -344,6 +346,7 @@ " lidar 10 + true @@ -415,6 +418,7 @@ 30 true rgbd_camera + true diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index 827abab211..985bec6a97 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; } @@ -232,8 +240,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; } @@ -255,8 +264,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; } @@ -271,8 +281,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; } @@ -288,8 +299,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; } @@ -305,8 +317,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; } @@ -322,8 +335,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; } @@ -339,8 +353,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; } @@ -356,8 +371,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; } @@ -373,8 +389,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; } @@ -389,8 +406,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; } @@ -406,8 +424,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; } @@ -423,8 +442,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; } @@ -441,8 +461,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; } @@ -458,8 +479,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; } @@ -476,8 +498,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; } @@ -493,8 +516,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; } @@ -510,8 +534,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; } @@ -528,8 +553,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; } @@ -545,8 +571,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; } @@ -562,8 +589,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; } @@ -579,8 +607,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; } @@ -596,8 +625,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; } @@ -612,8 +642,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; } @@ -630,8 +661,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 2c8fe2fb06..6a7869f528 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -82,7 +82,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. /// @@ -103,7 +103,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. @@ -112,11 +112,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); @@ -284,7 +286,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. @@ -299,7 +301,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 @@ -316,7 +318,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. @@ -471,7 +473,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. @@ -491,7 +493,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; @@ -519,14 +521,14 @@ 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[out] _state The serialized state message to populate. /// \param[in] _entities Entities to be serialized. Leave empty to get @@ -552,7 +554,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; @@ -561,7 +563,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 b0732dfa68..a4783b30b4 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); @@ -326,12 +326,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 @@ -340,7 +340,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 0fc3c3b8d7..758ac65c00 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -245,7 +245,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 d4c66c6e20..5e280a906c 100644 --- a/include/ignition/gazebo/components/Factory.hh +++ b/include/ignition/gazebo/components/Factory.hh @@ -202,9 +202,9 @@ namespace components /// \brief Unregister a component so that the factory can't create instances /// of the component 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) { @@ -366,7 +366,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 df6e2b6c66..4d2a836869 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 36d1961d5e..73d91ee725 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -176,7 +176,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, @@ -218,7 +218,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/BaseView_TEST.cc b/src/BaseView_TEST.cc index 5e424542ea..855168266d 100644 --- a/src/BaseView_TEST.cc +++ b/src/BaseView_TEST.cc @@ -27,16 +27,13 @@ #include "ignition/gazebo/detail/BaseView.hh" #include "ignition/gazebo/detail/View.hh" +#include "../test/helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; -class BaseViewTest : public ::testing::Test +class BaseViewTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// diff --git a/src/ComponentFactory_TEST.cc b/src/ComponentFactory_TEST.cc index b9021aa605..e9adeb972a 100644 --- a/src/ComponentFactory_TEST.cc +++ b/src/ComponentFactory_TEST.cc @@ -22,16 +22,18 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Pose.hh" +#include "../test/helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class ComponentFactoryTest : public ::testing::Test +class ComponentFactoryTest : public InternalFixture<::testing::Test> { // Documentation inherited protected: void SetUp() override { - common::Console::SetVerbosity(4); + InternalFixture::SetUp(); common::setenv("IGN_DEBUG_COMPONENT_FACTORY", "true"); } }; diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 963948a850..9451cee170 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -29,15 +29,17 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/EntityComponentManager.hh" +#include "../test/helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; ////////////////////////////////////////////////// -class ComponentTest : public ::testing::Test +class ComponentTest : public InternalFixture<::testing::Test> { protected: void SetUp() override { - common::Console::SetVerbosity(4); + InternalFixture::SetUp(); common::setenv("IGN_DEBUG_COMPONENT_FACTORY", "true"); } }; diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index dae5244665..9d7b8b5176 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -27,6 +27,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/config.hh" +#include "../test/helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; @@ -99,12 +100,9 @@ class EntityCompMgrTest : public EntityComponentManager } }; -class EntityComponentManagerFixture : public ::testing::TestWithParam +class EntityComponentManagerFixture + : public InternalFixture<::testing::TestWithParam> { - public: void SetUp() override - { - common::Console::SetVerbosity(4); - } public: EntityCompMgrTest manager; }; diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 9bdbae40be..eac28eef0c 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -53,6 +53,8 @@ #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/SdfEntityCreator.hh" +#include "../test/helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; @@ -66,12 +68,8 @@ class EntityCompMgrTest : public gazebo::EntityComponentManager }; ///////////////////////////////////////////////// -class SdfEntityCreatorTest : public ::testing::Test +class SdfEntityCreatorTest : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } public: EntityCompMgrTest ecm; public: EventManager evm; }; diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 4637c67439..41da6029b6 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -40,6 +40,7 @@ #include "ignition/gazebo/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" +#include "helpers/EnvTestFixture.hh" #include "SdfGenerator.hh" @@ -186,11 +187,11 @@ TEST(CompareElements, CompareWithDuplicateElements) } ///////////////////////////////////////////////// -class ElementUpdateFixture : public ::testing::Test +class ElementUpdateFixture : public InternalFixture<::testing::Test> { public: void SetUp() override { - ignition::common::Console::SetVerbosity(4); + InternalFixture::SetUp(); fuel_tools::ClientConfig config; config.SetCacheLocation(test::UniqueTestDirectoryEnv::Path()); diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index f49b6123e8..2498630072 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -234,12 +234,8 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) if (sdfUseLogRecord) { - bool hasCompress {false}; - bool sdfCompress; std::tie(sdfRecordResources, hasRecordResources) = recordPluginElem->Get("record_resources", false); - std::tie(sdfCompress, hasCompress) = - recordPluginElem->Get("compress", false); hasRecordTopics = recordPluginElem->HasElement("record_topic"); if (hasRecordTopics) diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index c429567289..44fe814cda 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -44,6 +44,11 @@ using namespace ignition; using namespace ignition::gazebo; using namespace std::chrono_literals; +///////////////////////////////////////////////// +class ServerFixture : public InternalFixture<::testing::TestWithParam> +{ +}; + ///////////////////////////////////////////////// TEST_P(ServerFixture, DefaultServerConfig) { diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 89d9afeffe..cd2a864eb1 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -56,6 +56,7 @@ #include "ignition/gazebo/Events.hh" #include "ignition/gazebo/Util.hh" #include "ignition/gazebo/config.hh" +#include "../test/helpers/EnvTestFixture.hh" #include "SimulationRunner.hh" using namespace ignition; @@ -81,16 +82,10 @@ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", } } -class SimulationRunnerTest : public ::testing::TestWithParam +///////////////////////////////////////////////// +class SimulationRunnerTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - common::joinPaths(PROJECT_BINARY_PATH, "lib")); - } }; std::vector clockMsgs; diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc index 244e5b1846..4c6d244f87 100644 --- a/src/TestFixture_TEST.cc +++ b/src/TestFixture_TEST.cc @@ -23,20 +23,15 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/ServerConfig.hh" #include "ignition/gazebo/test_config.hh" +#include "../test/helpers/EnvTestFixture.hh" #include "ignition/gazebo/TestFixture.hh" using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class TestFixtureTest : public ::testing::Test +class TestFixtureTest : public InternalFixture<::testing::Test> { - // Documentation inherited - public: void SetUp() override - { - common::Console::SetVerbosity(4); - } - /// \brief Configure expectations public: void Configure(const Entity &_entity, const std::shared_ptr &_sdf, diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index b927601c39..ac83bf2643 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -36,17 +36,14 @@ #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/Util.hh" +#include "helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; /// \brief Tests for Util.hh -class UtilTest : public ::testing::Test +class UtilTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 7c61a211dc..96bd3c952b 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -28,15 +28,21 @@ #include "ignition/gazebo/gui/Gui.hh" #include "ignition/gazebo/test_config.hh" +#include "../../test/helpers/EnvTestFixture.hh" + int gg_argc = 1; char **gg_argv = new char *[gg_argc]; using namespace ignition; using namespace gazebo; +class GuiTest : public InternalFixture<::testing::Test> +{ +}; + ///////////////////////////////////////////////// // https://github.com/ignitionrobotics/ign-gazebo/issues/8 -TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager)) +TEST_F(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager)) { common::Console::SetVerbosity(4); igndbg << "Start test" << std::endl; 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/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 3dd0258575..3255416565 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -466,12 +466,6 @@ void ComponentInspector::Update(const UpdateInfo &, continue; } - if (typeId == components::Light::typeId) - { - this->SetType("light"); - continue; - } - if (typeId == components::Actor::typeId) { this->SetType("actor"); 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/joint_position_controller/JointPositionController_TEST.cc b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc index 0b01af0ad0..19f2a0da85 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc @@ -39,6 +39,7 @@ #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/test_config.hh" +#include "../../../../test/helpers/EnvTestFixture.hh" #include "../../GuiRunner.hh" #include "JointPositionController.hh" @@ -49,13 +50,8 @@ char **g_argv; using namespace ignition; /// \brief Tests for the joint position controller GUI plugin -class JointPositionControllerGui : public ::testing::Test +class JointPositionControllerGui : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// 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/plot_3d/Plot3D_TEST.cc b/src/gui/plugins/plot_3d/Plot3D_TEST.cc index cd74822ee0..916a0609b3 100644 --- a/src/gui/plugins/plot_3d/Plot3D_TEST.cc +++ b/src/gui/plugins/plot_3d/Plot3D_TEST.cc @@ -40,6 +40,7 @@ #include "ignition/gazebo/components/ParentEntity.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/test_config.hh" +#include "../../../../test/helpers/EnvTestFixture.hh" #include "../../GuiRunner.hh" @@ -54,13 +55,8 @@ char* g_argv[] = using namespace ignition; /// \brief Tests for the joint position controller GUI plugin -class Plot3D : public ::testing::Test +class Plot3D : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.hh b/src/gui/plugins/resource_spawner/ResourceSpawner.hh index 2dd222534e..d886b9688a 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.hh +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.hh @@ -213,6 +213,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); @@ -232,7 +234,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.cc b/src/gui/plugins/scene3d/Scene3D.cc index 52ecbf7480..2522a5bf2f 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -642,6 +642,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) { IGN_PROFILE("IgnRenderer::Render Pre-render camera"); this->dataPtr->camera->PreRender(); + this->dataPtr->camera->Render(); } // mark mouse dirty to force update view projection in HandleMouseEvent this->dataPtr->mouseDirty = true; diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 971bd8a428..28c15227be 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -298,11 +298,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 @@ -365,7 +365,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 @@ -505,7 +505,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; @@ -673,11 +673,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 @@ -740,7 +740,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 f4e71ad0b2..daed2743e0 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -39,9 +39,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/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 1636cf80e3..a972b6faf9 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -23,6 +23,7 @@ #include #include +#include #include #include diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index dd972434fc..c74a9b5b24 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1017,18 +1017,23 @@ void RenderUtil::Update() this->dataPtr->sceneManager.CreateLight( std::get<0>(light), std::get<1>(light), std::get<2>(light)); - // create a new id for the light visual - auto attempts = 100000u; - for (auto i = 0u; i < attempts; ++i) + // TODO(anyone) This needs to be updated for when sensors and GUI use + // the same scene + // create a new id for the light visual, if we're not loading sensors + if (!this->dataPtr->enableSensors) { - Entity id = std::numeric_limits::min() + i; - if (!this->dataPtr->sceneManager.HasEntity(id)) + auto attempts = 100000u; + for (auto i = 0u; i < attempts; ++i) { - rendering::VisualPtr lightVisual = - this->dataPtr->sceneManager.CreateLightVisual( - id, std::get<1>(light), std::get<0>(light)); - this->dataPtr->matchLightWithVisuals[std::get<0>(light)] = id; - break; + Entity id = std::numeric_limits::min() + i; + if (!this->dataPtr->sceneManager.HasEntity(id)) + { + rendering::VisualPtr lightVisual = + this->dataPtr->sceneManager.CreateLightVisual( + id, std::get<1>(light), std::get<0>(light)); + this->dataPtr->matchLightWithVisuals[std::get<0>(light)] = id; + break; + } } } } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 283c12f1d5..ee19fae158 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -356,7 +356,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/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 454d3b56ea..66ee000dfa 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -21,6 +21,7 @@ #include #include +#include #include #include #include @@ -33,9 +34,10 @@ #include #include -#include +#include #include #include +#include #include #include @@ -244,9 +246,55 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate return true; }); + std::vector lights; + _ecm.Each( + [&](const Entity &/*_entity*/, + const components::Light *_light, + const components::Name *_name)->bool + { + std::string name = _name->Data(); + const auto& sdfLight = _light->Data(); + + common::ColladaLight p; + p.name = name; + if (sdfLight.Type() == sdf::LightType::POINT) + { + p.type = "point"; + } + else if (sdfLight.Type() == sdf::LightType::SPOT) + { + p.type = "spot"; + } + else if (sdfLight.Type() == sdf::LightType::DIRECTIONAL) + { + p.type = "directional"; + } + else + { + p.type = "invalid"; + } + + p.position = sdfLight.RawPose().Pos(); + p.direction = sdfLight.RawPose().Rot().RotateVector(sdfLight.Direction()); + p.diffuse = sdfLight.Diffuse(); + + p.constantAttenuation = sdfLight.ConstantAttenuationFactor(); + p.linearAttenuation = sdfLight.LinearAttenuationFactor(); + p.quadraticAttenuation = sdfLight.QuadraticAttenuationFactor(); + + // Falloff angle is treated as the outer angle in blender + // https://community.khronos.org/t/spotlight-properties/7111/7 + p.falloffAngleDeg = sdfLight.SpotOuterAngle().Degree(); + p.falloffExponent = sdfLight.SpotFalloff(); + + lights.push_back(p); + return true; + }); + common::ColladaExporter exporter; exporter.Export(&worldMesh, "./" + worldMesh.Name(), true, - subMeshMatrix); + subMeshMatrix, lights); ignmsg << "The world has been exported into the " << "./" + worldMesh.Name() << " directory." << std::endl; this->exported = true; 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: /// - /// A new audio source in the environment, which has the + /// - `` A new audio source in the environment, which has the /// following child elements: - /// * The source ID, which must be unique and an integer >= 0. + /// + `` The source ID, which must be unique and an integer >= 0. /// An ID < 0 results in undefined behavior. /// The ID must be unique within the scope of all other source IDs /// in the plugin's parent element - so, if a source was created in a - /// with an ID of 1, no other sources in the same model can have - /// an ID of 1 (however, sources that belong to other models can have an - /// ID of 1). - /// * The pose, expressed as "x y z roll pitch yaw". + /// `` with an ID of 1, no other sources in the same model can + /// have an ID of 1 (however, sources that belong to other models can + /// have an ID of 1). + /// + `` The pose, expressed as "x y z roll pitch yaw". /// Each pose coordinate must be separated by whitespace. /// The pose is defined relative to the plugin's parent element. - /// So, if the plugin is used inside of a tag, then the - /// source's is relative to the model's pose. - /// If the plugin is used inside of a tag, then the source's - /// is relative to the world (i.e., specifies an + /// So, if the plugin is used inside of a `` tag, then the + /// source's `` is relative to the model's pose. + /// If the plugin is used inside of a `` tag, then the source's + /// `` is relative to the world (i.e., `` specifies an /// absolute pose). /// If no pose is specified, {0, 0, 0, 0, 0, 0} will be used. - /// * The attenuation function. + /// + `` The attenuation function. /// See logical_audio::AttenuationFunction for a list of valid /// attenuation functions, and logical_audio::SetAttenuationFunction /// for how to specify an attenuation function in SDF. - /// * The attenuation shape. + /// + `` The attenuation shape. /// See logical_audio::AttenuationShape for a list of valid /// attenuation shapes, and logical_audio::SetAttenuationShape for how /// to specify an attenuation shape in SDF. - /// * The inner radius of the attenuation shape. + /// + `` The inner radius of the attenuation shape. /// This value must be >= 0.0. The volume of the source will be - /// at locations that have a distance <= inner + /// `` at locations that have a distance <= inner /// radius from the source. - /// * The falloff distance. This value must be greater - /// than the value of the source's . This defines the - /// distance from the audio source where the volume becomes 0. - /// * The volume level emitted from the source. This must + /// + `` The falloff distance. This value must be + /// greater than the value of the source's ``. This + /// defines the distance from the audio source where the volume + /// becomes 0. + /// + `` The volume level emitted from the source. This must /// be a value between 0.0 and 1.0 (representing 0% to 100%). - /// * Whether the source should play immediately or not. + /// + `` Whether the source should play immediately or not. /// Use true to initiate audio immediately, and false otherwise. - /// * The duration (in seconds) audio is played from the + /// + `` The duration (in seconds) audio is played from the /// source. This value must be an integer >= 0. /// A value of 0 means that the source will play for an infinite amount /// of time. /// /// Specifying a microphone via SDF is done as follows: /// - /// A new microphone in the environment, + /// - `` A new microphone in the environment, /// which has the following child elements: - /// * The microphone ID, which must be unique and an integer >= 0. + /// + `` The microphone ID, which must be unique and an integer >= 0. /// An ID < 0 results in undefined behavior. /// The ID must be unique within the scope of all other microphone IDs /// in the plugin's parent element - so, if a microphone was created in - /// a with an ID of 1, no other microphones in the same model + /// a `` with an ID of 1, no other microphones in the same model /// can have an ID of 1 (however, microphones that belong to other /// models can have an ID of 1). - /// * The pose, expressed as "x y z roll pitch yaw". + /// + `` The pose, expressed as "x y z roll pitch yaw". /// Each pose coordinate must be separated by whitespace. /// The pose is defined relative to the plugin's parent element. - /// So, if the plugin is used inside of a tag, then the - /// source's is relative to the model's pose. - /// If the plugin is used inside of a tag, then the source's - /// is relative to the world (i.e., specifies an + /// So, if the plugin is used inside of a `` tag, then the + /// source's ``is relative to the model's pose. + /// If the plugin is used inside of a `` tag, then the source's + /// `` is relative to the world (i.e., `` specifies an /// absolute pose). /// If no pose is specified, {0, 0, 0, 0, 0, 0} will be used. - /// * The minimum volume level the microphone + /// + `` The minimum volume level the microphone /// can detect. This must be a value between 0.0 and 1.0 /// (representing 0% to 100%). /// If no volume threshold is specified, 0.0 will be used. /// /// Sources can be started and stopped via Ignition service calls. /// If a source is successfully created, the following services will be - /// created for the source ( is the scoped name for the source - see - /// ignition::gazebo::scopedName for more details - and is the value - /// specified in the source's tag from the SDF): - /// * /source_/play + /// created for the source (`` is the scoped name for the source - see + /// ignition::gazebo::scopedName for more details - and `` is the value + /// specified in the source's `` tag from the SDF): + /// * `/source_/play` /// * Starts playing the source with the specified ID. /// If the source is already playing, nothing happens. - /// * /source_/stop + /// * `/source_/stop` /// * Stops playing the source with the specified ID. /// If the source is already stopped, nothing happens. /// /// Microphone detection information can be retrieved via Ignition topics. /// Whenever a microphone detects a source, it publishes a message to the - /// /mic_/detection topic, where is the scoped name + /// `/mic_/detection` topic, where `` is the scoped name /// for the microphone - see ignition::gazebo::scopedName for more details - - /// and is the value specified in the microphone's tag from the SDF. + /// and `` is the value specified in the microphone's `` tag from the + /// SDF. class LogicalAudioSensorPlugin : public System, public ISystemConfigure, diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 72b73015f1..0fe9d7ece6 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -126,11 +126,11 @@ namespace systems /// value of 0 implies noise is NOT applied to the component. The default /// value is (0, 0, 0). /// - /// rotorConfiguration: This contains a list of elements for each + /// rotorConfiguration: This contains a list of `` elements for each /// rotor in the vehicle. This is a required parameter. /// /// rotor: Contains information about a rotor in the vehicle. All the - /// elements of are required parameters. + /// elements of `` are required parameters. /// /// jointName: The name of the joint associated with this rotor. /// diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index ea0ad9438e..72d651b121 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -55,8 +55,8 @@ namespace systems /// header will also contain the key "count" with a value set to the /// number of performers currently in the region. /// - /// The PerformerDetector has to be attached to a and it's region is - /// centered on the containing model's origin. + /// The PerformerDetector has to be attached to a `` and it's region + /// is centered on the containing model's origin. /// /// The system does not assume that levels are enabled, but it does require /// performers to be specified. diff --git a/src/systems/physics/EntityFeatureMap.hh b/src/systems/physics/EntityFeatureMap.hh index 8008f478d7..933accc9fa 100644 --- a/src/systems/physics/EntityFeatureMap.hh +++ b/src/systems/physics/EntityFeatureMap.hh @@ -142,7 +142,7 @@ namespace systems::physics_system /// to an entity with a different set of features. This overload takes a /// physics entity as input /// \tparam ToFeatureList The list of features of the resulting entity. - /// \param[in] _entity Physics entity with required features. + /// \param[in] _physicsEntity Physics entity with required features. /// \return Physics entity with features in ToFeatureList. nullptr if the /// entity can't be found or the physics engine doesn't support the /// requested feature. @@ -252,7 +252,7 @@ namespace systems::physics_system } /// \brief Remove physics entity from all associated maps - /// \param[in] _entity Gazebo entity. + /// \param[in] _physicsEntity Physics entity. /// \return True if the entity was found and removed. public: bool Remove(const RequiredEntityPtr &_physicsEntity) { diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index e315735cd1..d96daf60cd 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -30,6 +30,7 @@ #include #include +#include "../../../test/helpers/EnvTestFixture.hh" #include "ignition/gazebo/EntityComponentManager.hh" using namespace ignition; @@ -46,10 +47,12 @@ using EnginePtrType = physics::EnginePtr; -class EntityFeatureMapFixture: public ::testing::Test +class EntityFeatureMapFixture: public InternalFixture<::testing::Test> { protected: void SetUp() override { + InternalFixture::SetUp(); + const std::string pluginLib = "libignition-physics-dartsim-plugin.so"; common::SystemPaths systemPaths; diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index b74097d751..251fc2e8bf 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -42,21 +42,22 @@ namespace systems /// /// Parameters: /// - /// Scoped name of the desired collision entity that is checked to - /// see if it's touching this model. This can be a substring of the - /// desired collision name so we match more than one collision. For - /// example, using the name of a model will match all its collisions. + /// - `` Scoped name of the desired collision entity that is checked + /// to see if it's touching this model. This can be a substring + /// of the desired collision name so we match more than one + /// collision. For example, using the name of a model will match + /// all its collisions. /// - ///