Skip to content

Commit

Permalink
Merge pull request #874 from ignitionrobotics/merge_12_to_main
Browse files Browse the repository at this point in the history
Merge sdf12 to main
  • Loading branch information
scpeters authored Mar 9, 2022
2 parents c2ef096 + ee3816b commit f174efc
Show file tree
Hide file tree
Showing 116 changed files with 6,366 additions and 69 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@ jobs:
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-enabled: true
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
Expand All @@ -28,3 +26,5 @@ jobs:
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
with:
codecov-enabled: true
20 changes: 20 additions & 0 deletions include/sdf/Actor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "sdf/Types.hh"
#include "sdf/Link.hh"
#include "sdf/Joint.hh"
#include "sdf/Plugin.hh"
#include "sdf/sdf_config.h"
#include "sdf/system_util.hh"

Expand Down Expand Up @@ -380,9 +381,28 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// actor.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated actor values.
public: sdf::ElementPtr ToElement() const;

/// \brief Get the plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: const sdf::Plugins &Plugins() const;

/// \brief Get a mutable vector of plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: sdf::Plugins &Plugins();

/// \brief Remove all plugins
public: void ClearPlugins();

/// \brief Add a plugin to this object.
/// \param[in] _plugin Plugin to add.
public: void AddPlugin(const Plugin &_plugin);

/// \brief Private data pointer.
IGN_UTILS_IMPL_PTR(dataPtr)
};
Expand Down
2 changes: 2 additions & 0 deletions include/sdf/AirPressure.hh
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// air pressure sensor.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Altimeter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// altimeter sensor.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Atmosphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// atmosphere.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated atmosphere values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// box.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated box values.
public: sdf::ElementPtr ToElement() const;

Expand Down
18 changes: 18 additions & 0 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,22 @@ namespace sdf
/// \param[in] _name Name of the sensor.
public: void SetName(const std::string &_name);

/// \brief Get whether the camera is triggered by a topic.
/// \return True if the camera is triggered by a topic.
public: bool Triggered() const;

/// \brief Set whether the camera should be triggered by a topic.
/// \param[in] _triggered True if the camera should be triggered by a topic.
public: void SetTriggered(bool _triggered);

/// \brief Get the topic that will trigger the camera.
/// \return Topic for the camera trigger.
public: std::string TriggerTopic() const;

/// \brief Set the topic that will trigger the camera.
/// \param[in] _triggerTopic Topic for the camera trigger.
public: void SetTriggerTopic(const std::string &_triggerTopic);

/// \brief Get the horizontal field of view in radians.
/// \return The horizontal field of view in radians.
public: ignition::math::Angle HorizontalFov() const;
Expand Down Expand Up @@ -474,6 +490,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// camera.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated camera values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Capsule.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// capsule.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated capsule values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Collision.hh
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// collision.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated collision values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// cylinder.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated cylinder values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Ellipsoid.hh
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// ellipsoid.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated ellipsoid values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/ForceTorque.hh
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// force torque sensor.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Geometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// geometry.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated geometry values.
public: sdf::ElementPtr ToElement() const;

Expand Down
14 changes: 13 additions & 1 deletion include/sdf/Gui.hh
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// gui.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated gui values.
public: sdf::ElementPtr ToElement() const;

Expand All @@ -81,10 +83,20 @@ namespace sdf
/// \brief Remove all plugins
public: void ClearPlugins();

/// \brief Add a plugin to the link.
/// \brief Add a plugin to this object.
/// \param[in] _plugin Plugin to add.
public: void AddPlugin(const Plugin &_plugin);

/// \brief Get the plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: const sdf::Plugins &Plugins() const;

/// \brief Get a mutable vector of plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: sdf::Plugins &Plugins();

/// \brief Private data pointer.
IGN_UTILS_IMPL_PTR(dataPtr)
};
Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Heightmap.hh
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// heightmap.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated heightmap values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Imu.hh
Original file line number Diff line number Diff line change
Expand Up @@ -255,6 +255,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// imu sensor.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -227,6 +227,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// joint.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated joint values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/JointAxis.hh
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// joint axis.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \param[in] _index Index of this joint axis
/// \return SDF element pointer with updated joint values.
public: sdf::ElementPtr ToElement(unsigned int _index = 0u) const;
Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -234,6 +234,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// lidar.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
10 changes: 10 additions & 0 deletions include/sdf/Light.hh
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,14 @@ namespace sdf
/// \param[in] _cast True to indicate that the light casts shadows.
public: void SetCastShadows(const bool _cast);

/// \brief Get if the light is on
/// \return True if the light is on.
public: bool LightOn() const;

/// \brief Set if the light is ON/OFF
/// \param[in] _cast True to indicate that the light is on, False otherwise.
public: void SetLightOn(const bool _isLightOn);

/// \brief Get the light intensity
/// \return The light intensity
public: double Intensity() const;
Expand Down Expand Up @@ -270,6 +278,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// light object.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated light values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// link.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated link values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Magnetometer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// magnetometer.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated sensor values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Material.hh
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// material.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated material values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Mesh.hh
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// mesh.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated mesh values.
public: sdf::ElementPtr ToElement() const;

Expand Down
32 changes: 32 additions & 0 deletions include/sdf/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <ignition/math/Pose3.hh>
#include <ignition/utils/ImplPtr.hh>
#include "sdf/Element.hh"
#include "sdf/Plugin.hh"
#include "sdf/SemanticPose.hh"
#include "sdf/Types.hh"
#include "sdf/sdf_config.h"
Expand Down Expand Up @@ -417,6 +418,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// model.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \param[in] _useIncludeTag When true, the model's URI is used to create
/// an SDF `<include>` rather than a `<model>`. The model's URI must be
/// first set using the `Model::SetUri` function. If the model's URI is
Expand All @@ -428,6 +431,18 @@ namespace sdf
/// \return SDF element pointer with updated model values.
public: sdf::ElementPtr ToElement(bool _useIncludeTag = true) const;

/// \brief Check if a given name exists in the FrameAttachedTo graph at the
/// scope of the model.
/// \param[in] _name Name of the implicit or explicit frame to check.
/// To check for a frame in a nested model, prefix the frame name with
/// the sequence of nested models containing this frame, delimited by "::".
/// \return True if the frame name is found in the FrameAttachedTo graph.
/// False otherwise, or if the frame graph is invalid.
/// \note This function assumes the model has a valid FrameAttachedTo graph.
/// It will return false if the graph is invalid.
public: bool NameExistsInFrameAttachedToGraph(
const std::string &_name) const;

/// \brief Add a link to the model.
/// \param[in] _link Link to add.
/// \return True if successful, false if a link with the name already
Expand Down Expand Up @@ -472,6 +487,23 @@ namespace sdf
/// \param[in] _uri The model's URI.
public: void SetUri(const std::string &_uri);

/// \brief Get the plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: const sdf::Plugins &Plugins() const;

/// \brief Get a mutable vector of plugins attached to this object.
/// \return A vector of Plugin, which will be empty if there are no
/// plugins.
public: sdf::Plugins &Plugins();

/// \brief Remove all plugins
public: void ClearPlugins();

/// \brief Add a plugin to this object.
/// \param[in] _plugin Plugin to add.
public: void AddPlugin(const Plugin &_plugin);

/// \brief Give the scoped PoseRelativeToGraph to be used for resolving
/// poses. This is private and is intended to be called by Root::Load or
/// World::SetPoseRelativeToGraph if this is a standalone model and
Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Noise.hh
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// noise.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated noise values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/ParticleEmitter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -318,6 +318,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// particle emitter.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated particle emitter values.
public: sdf::ElementPtr ToElement() const;

Expand Down
2 changes: 2 additions & 0 deletions include/sdf/Physics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,8 @@ namespace sdf

/// \brief Create and return an SDF element filled with data from this
/// physics.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \return SDF element pointer with updated physics values.
public: sdf::ElementPtr ToElement() const;

Expand Down
Loading

0 comments on commit f174efc

Please sign in to comment.