Skip to content

Commit

Permalink
ign -> gz: namespaces and logging functions (#356)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>

Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
methylDragon and chapulina authored May 28, 2022
1 parent 6fa6fda commit c021582
Show file tree
Hide file tree
Showing 311 changed files with 2,778 additions and 2,526 deletions.
2 changes: 1 addition & 1 deletion CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -1 +1 @@
See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing).
See the [Gazebo contributing guide](https://gazebosim.org/docs/all/contributing).
338 changes: 169 additions & 169 deletions Changelog.md

Large diffs are not rendered by default.

20 changes: 12 additions & 8 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,19 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Common 4.X to 5.X
## Gazebo Common 4.X to 5.X

### Deprecations

1. `Submesh::MaterialIndex` is deprecated. `SubMesh::GetMaterialIndex` should
be used instead, which properly handles submeshes having no material index
applied to them.
2. The `ignition` namespace is deprecated and will be removed in future versions. Use `gz` instead.
3. Header files under `ignition/...` are deprecated and will be removed in future versions.
Use `gz/...` instead.
4. The logging macros (`ignmsg`, `ignwarn`, `ignerr`, etc.) and logging function macros
(`ignLogInit()`, etc.) are deprecated and will be removed in future versions. Use `gz` instead
(e.g. `gzmsg`, `gzwarn`, `gzLogInit()`)

1. All the plugin APIs are deprecated, use the gz-plugin library instead. See
the [migration guide](https://github.com/ignitionrobotics/ign-plugin/blob/ign-plugin1/MIGRATION.md).
Expand All @@ -33,7 +39,7 @@ release will remove the deprecated code.

1. `Image::AvgColor`, `Image::Data` and `Image::RGBData` methods are now `const`.

## Ignition Common 3.X to 4.X
## Gazebo Common 3.X to 4.X

### Modifications

Expand All @@ -47,10 +53,9 @@ release will remove the deprecated code.
* A URI Query does not require a `key=value` format. For example
a valid query can be "?aquery", "?aquery?", and `??`.
* A URI authority is optional. If present, then a URI authority begins
with two forward slashes and immediately follows the URI scheme. A host
must be present if an authority is present and the scheme != 'file'.
with two forward slashes and immediately follows the URI scheme. A host must be present if an authority is present and the scheme != 'file'.

## Ignition Common 2.X to 3.X
## Gazebo Common 2.X to 3.X

### Additions

Expand All @@ -77,7 +82,7 @@ release will remove the deprecated code.

1. (New in 3.8.0) On Windows, the value of C++ macro `IGN_HOMEDIR` changed from `HOMEPATH` to `USERPROFILE`. It is usually used to read the path to the user's home from environment. The old value pointed to a path relative to the (a) current drive letter as reported by `pwd`, not the system drive letter. The new value correctly points to an environment variable that contains the full absolute path to the user's profile. If the code did not use the macro in some unexpected way, the new behavior should work either the same or even better (it would work even when the current directory is on a non-system drive). If the code relied on this value to be relative to the current drive letter, it needs to be changed to use `HOMEPATH` directly.

## Ignition Common 1.X to 2.X
## Gazebo Common 1.X to 2.X

### Modifications

Expand All @@ -93,11 +98,10 @@ release will remove the deprecated code.
- events: registering and handling event callbacks
- graphics: animation, images, and triangle meshes

## Ignition Common 0.X to 1.X
## Gazebo Common 0.X to 1.X

### Added dependencies

1. **ignition-cmake**
+ Ignition-math now has a build dependency on ignition-cmake, which
allows cmake scripts to be shared across all the ignition packages.

28 changes: 14 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,25 +1,25 @@
# Ignition Common : AV, Graphics, Events, and much more.
# Gazebo Common : AV, Graphics, Events, and much more.

**Maintainer:** nate AT openrobotics DOT org

[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-common.svg)](https://github.com/ignitionrobotics/ign-common/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-common.svg)](https://github.com/ignitionrobotics/ign-common/pulls)
[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-common.svg)](https://github.com/gazebosim/gz-common/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-common.svg)](https://github.com/gazebosim/gz-common/pulls)
[![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org)
[![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0)

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

Ignition Common, a component of [Ignition
Robotics](https://ignitionrobotics.org), provides a set of libraries that
Gazebo Common, a component of [Ignition
Robotics](https://gazebosim.org), provides a set of libraries that
cover many different use cases. An audio-visual library supports
processing audio and video files, a graphics library can load a variety 3D
mesh file formats into a generic in-memory representation, and the core
library of Ignition Common contains functionality that spans Base64
library of Gazebo Common contains functionality that spans Base64
encoding/decoding to thread pools.

# Table of Contents
Expand All @@ -42,7 +42,7 @@ encoding/decoding to thread pools.

# Features

Some of the many capabilities contained in Ignition Common are:
Some of the many capabilities contained in Gazebo Common are:

* **AV**: FFMpeg based audio decoder, and video encoder and decoder.
* **Core**: Base64 encoding and decoding, battery model, console logging,
Expand All @@ -56,11 +56,11 @@ callback system.

# Install

See the [installation tutorial](https://ignitionrobotics.org/api/common/4.0/tutorials.html).
See the [installation tutorial](https://gazebosim.org/api/common/4.0/tutorials.html).

# Usage

Please refer to the [examples directory](https://github.com/ignitionrobotics/ign-common/raw/main/examples/).
Please refer to the [examples directory](https://github.com/gazebosim/gz-common/raw/main/examples/).

# Folder Structure

Expand Down Expand Up @@ -88,18 +88,18 @@ Refer to the following table for information about important directories and fil
# Contributing

Please see
[CONTRIBUTING.md](https://ignitionrobotics.org/docs/all/contributing).
[CONTRIBUTING.md](https://gazebosim.org/docs/all/contributing).

# Code of Conduct

Please see
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md).
[CODE_OF_CONDUCT.md](https://github.com/gazebosim/gz-sim/blob/main/CODE_OF_CONDUCT.md).

# Versioning

This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information.
This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Gazebo project](https://gazebosim.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Gazebo website](https://gazebosim.org) for version and release information.

# License

This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-common/blob/main/LICENSE) file.
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/gazebosim/gz-common/blob/main/LICENSE) file.

2 changes: 1 addition & 1 deletion api.md.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
## Ignition @IGN_DESIGNATION_CAP@

Ignition @IGN_DESIGNATION_CAP@ is a component in Ignition Robotics, a set of libraries
Ignition @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries
designed to rapidly develop robot and simulation applications.

## License
Expand Down
4 changes: 2 additions & 2 deletions av/include/gz/common/AudioDecoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,13 @@
#include <gz/common/av/Export.hh>
#include <gz/utils/ImplPtr.hh>

namespace ignition
namespace gz
{
namespace common
{
/// \class AudioDecoder AudioDecoder.hh gz/common/common.hh
/// \brief An audio decoder based on FFMPEG.
class IGNITION_COMMON_AV_VISIBLE AudioDecoder
class GZ_COMMON_AV_VISIBLE AudioDecoder
{
/// \brief Constructor.
public: AudioDecoder();
Expand Down
6 changes: 3 additions & 3 deletions av/include/gz/common/HWEncoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,12 @@

/// This is an internal-use only class encapsulating HW video encoding. All
/// symbols defined here are hidden from the public API.
namespace ignition::common
namespace gz::common
{
/// \brief Representation of a GPU video encoder and its configuration.
/// \note This class is intentionally hidden as it provides highly customized
/// behavior tailored just for the use with VideoEncoder.
class IGNITION_COMMON_AV_HIDDEN HWEncoder
class GZ_COMMON_AV_HIDDEN HWEncoder
{
/// \brief Set up the HW encoder configurator.
/// \param[in] _allowedHwEncoders HW encoders to try.
Expand Down Expand Up @@ -62,7 +62,7 @@ namespace ignition::common
/// \param[in] _encoderContext Context of the encoder for which hardware
/// acceleration should be set up.
/// \note If the configuration fails, the codec will be left configured for
/// software encoding and an error will be written to ignerr describing what
/// software encoding and an error will be written to gzerr describing what
/// failed.
public: void ConfigHWAccel(AVCodecContext* _encoderContext);

Expand Down
4 changes: 2 additions & 2 deletions av/include/gz/common/HWVideo.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@

#include <gz/common/EnumIface.hh>

namespace ignition::common
namespace gz::common
{
enum class IGNITION_COMMON_AV_VISIBLE HWEncoderType
enum class GZ_COMMON_AV_VISIBLE HWEncoderType
{
NONE,
NVENC, // Linux device is /dev/nvidia*
Expand Down
4 changes: 2 additions & 2 deletions av/include/gz/common/Video.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,12 @@ struct AVFrame;
struct AVPicture;
struct SwsContext;

namespace ignition
namespace gz
{
namespace common
{
/// \brief Handle video encoding and decoding using libavcodec
class IGNITION_COMMON_AV_VISIBLE Video
class GZ_COMMON_AV_VISIBLE Video
{
/// \brief Constructor
public: Video();
Expand Down
4 changes: 2 additions & 2 deletions av/include/gz/common/VideoEncoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@
#define VIDEO_ENCODER_FPS_DEFAULT 25
#define VIDEO_ENCODER_FORMAT_DEFAULT "mp4"

namespace ignition
namespace gz
{
namespace common
{
/// \brief The VideoEncoder class supports encoding a series of images
/// to a video format, and then writing the video to disk.
class IGNITION_COMMON_AV_VISIBLE VideoEncoder
class GZ_COMMON_AV_VISIBLE VideoEncoder
{
/// \brief Constructor
public: VideoEncoder();
Expand Down
2 changes: 1 addition & 1 deletion av/include/gz/common/av/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#ifndef GZ_COMMON_AV_UTIL_HH_
#define GZ_COMMON_AV_UTIL_HH_

namespace ignition
namespace gz
{
namespace common
{
Expand Down
10 changes: 5 additions & 5 deletions av/include/gz/common/ffmpeg_inc.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,21 +51,21 @@ extern "C" {

#include <gz/common/av/Export.hh>

namespace ignition
namespace gz
{
namespace common
{
/// \brief Helper function to avoid deprecation warnings.
IGNITION_COMMON_AV_VISIBLE
GZ_COMMON_AV_VISIBLE
AVFrame *AVFrameAlloc(void);

/// \brief Helper function to avoid deprecation warnings.
IGNITION_COMMON_AV_VISIBLE
GZ_COMMON_AV_VISIBLE
void AVFrameUnref(AVFrame *_frame);

/// \brief Helper function to avoid deprecation warnings.
/// \param[in] _packet AVPacket structure that stores compressed data
IGNITION_COMMON_AV_VISIBLE
GZ_COMMON_AV_VISIBLE
void AVPacketUnref(AVPacket *_packet);

/// \brief Helper function to avoid deprecation warnings
Expand All @@ -79,7 +79,7 @@ namespace ignition
/// the number of bytes used.
/// \note If the codec is in draining mode, _packet can be null. The return
/// value on success will then be 0, but _gotFrame will be non-zero.
IGNITION_COMMON_AV_VISIBLE
GZ_COMMON_AV_VISIBLE
int AVCodecDecode(AVCodecContext *_codecCtx,
AVFrame *_frame, int *_gotFrame, AVPacket *_packet);

Expand Down
1 change: 1 addition & 0 deletions av/include/ignition/common/AudioDecoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/AudioDecoder.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/HWEncoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/HWEncoder.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/HWVideo.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/HWVideo.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/Video.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/Video.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/VideoEncoder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/VideoEncoder.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/av.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/av.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/av/Export.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/av/Export.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/av/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/av/Util.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/av/detail/Export.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/av/detail/Export.hh>
#include <ignition/common/config.hh>
1 change: 1 addition & 0 deletions av/include/ignition/common/ffmpeg_inc.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/common/ffmpeg_inc.hh>
#include <ignition/common/config.hh>
Loading

0 comments on commit c021582

Please sign in to comment.