Skip to content

Commit

Permalink
Migrate sources and header references (#249)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed May 3, 2022
1 parent 78682bb commit 8c77114
Show file tree
Hide file tree
Showing 193 changed files with 437 additions and 437 deletions.
10 changes: 5 additions & 5 deletions include/gz/msgs/Factory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
* limitations under the License.
*
*/
#ifndef IGNITION_MSGS_FACTORY_HH_
#define IGNITION_MSGS_FACTORY_HH_
#ifndef GZ_MSGS_FACTORY_HH_
#define GZ_MSGS_FACTORY_HH_

#ifdef _MSC_VER
#pragma warning(push)
Expand All @@ -31,8 +31,8 @@
#include <memory>
#include <vector>

#include "ignition/msgs/config.hh"
#include "ignition/msgs/Export.hh"
#include "gz/msgs/config.hh"
#include "gz/msgs/Export.hh"

namespace ignition
{
Expand All @@ -45,7 +45,7 @@ namespace ignition
/// \brief Prototype for message factory generation
typedef std::unique_ptr<google::protobuf::Message> (*FactoryFn) ();

/// \class Factory Factory.hh ignition/msgs.hh
/// \class Factory Factory.hh gz/msgs.hh
/// \brief A factory that generates protobuf message based on a string type.
/// This class will also try to load all Protobuf descriptors specified
/// in the IGN_DESCRIPTOR_PATH environment variable on program start.
Expand Down
8 changes: 4 additions & 4 deletions include/gz/msgs/Filesystem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
*
*/

#ifndef IGNITION_MSGS_FILESYSTEM_HH_
#define IGNITION_MSGS_FILESYSTEM_HH_
#ifndef GZ_MSGS_FILESYSTEM_HH_
#define GZ_MSGS_FILESYSTEM_HH_

#include <memory>
#include <string>

#include <ignition/msgs/Export.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <gz/msgs/Export.hh>
#include <gz/utils/SuppressWarning.hh>

namespace ignition
{
Expand Down
10 changes: 5 additions & 5 deletions include/gz/msgs/PointCloudPackedUtils.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,18 @@
// Inspired by
// https:/ros/common_msgs/blob/275b09a/sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h

#ifndef IGNITION_MSGS_POINTCLOUDPACKEDUTILS_HH_
#define IGNITION_MSGS_POINTCLOUDPACKEDUTILS_HH_
#ifndef GZ_MSGS_POINTCLOUDPACKEDUTILS_HH_
#define GZ_MSGS_POINTCLOUDPACKEDUTILS_HH_

#include <ignition/msgs/pointcloud_packed.pb.h>
#include <gz/msgs/pointcloud_packed.pb.h>

#include <cstdarg>
#include <sstream>
#include <string>
#include <vector>

#include "ignition/msgs/config.hh"
#include "ignition/msgs/detail/PointCloudPackedUtils.hh"
#include "gz/msgs/config.hh"
#include "gz/msgs/detail/PointCloudPackedUtils.hh"

namespace ignition
{
Expand Down
6 changes: 3 additions & 3 deletions include/gz/msgs/SuppressWarning.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
*
*/

#ifndef IGNITION_MSGS_SUPPRESSWARNING_HH_
#define IGNITION_MSGS_SUPPRESSWARNING_HH_
#ifndef GZ_MSGS_SUPPRESSWARNING_HH_
#define GZ_MSGS_SUPPRESSWARNING_HH_

#include <ignition/utils/SuppressWarning.hh>
#include <gz/utils/SuppressWarning.hh>

#pragma message("ign-msgs SuppressWarning is deprecated, use ign-utils")

Expand Down
26 changes: 13 additions & 13 deletions include/gz/msgs/Utility.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,24 +14,24 @@
* limitations under the License.
*
*/
#ifndef IGNITION_MSGS_UTILITY_HH_
#define IGNITION_MSGS_UTILITY_HH_
#ifndef GZ_MSGS_UTILITY_HH_
#define GZ_MSGS_UTILITY_HH_

#include <string>
#include <utility>
#include <vector>

#include <ignition/math/AxisAlignedBox.hh>
#include <ignition/math/Color.hh>
#include <ignition/math/Inertial.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Plane.hh>
#include <ignition/math/SphericalCoordinates.hh>
#include <ignition/math/Vector3.hh>

#include "ignition/msgs/config.hh"
#include "ignition/msgs/Export.hh"
#include "ignition/msgs/MessageTypes.hh"
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/Color.hh>
#include <gz/math/Inertial.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Plane.hh>
#include <gz/math/SphericalCoordinates.hh>
#include <gz/math/Vector3.hh>

#include "gz/msgs/config.hh"
#include "gz/msgs/Export.hh"
#include "gz/msgs/MessageTypes.hh"

/// \file Utility.hh
/// \brief Utility functions that support conversion between message type
Expand Down
8 changes: 4 additions & 4 deletions include/gz/msgs/detail/PointCloudPackedUtils.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,15 @@
// Inspired by
// https:/ros/common_msgs/blob/275b09a/sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h

#ifndef IGNITION_MSGS_DETAIL_POINTCLOUDPACKEDUTILS_HH_
#define IGNITION_MSGS_DETAIL_POINTCLOUDPACKEDUTILS_HH_
#ifndef GZ_MSGS_DETAIL_POINTCLOUDPACKEDUTILS_HH_
#define GZ_MSGS_DETAIL_POINTCLOUDPACKEDUTILS_HH_

#include <ignition/msgs/pointcloud_packed.pb.h>
#include <gz/msgs/pointcloud_packed.pb.h>

#include <iostream>
#include <string>

#include "ignition/msgs/config.hh"
#include "gz/msgs/config.hh"

namespace ignition
{
Expand Down
6 changes: 3 additions & 3 deletions proto/gz/msgs/actor.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ option java_outer_classname = "ActorProtos";
/// \interface Actor
/// \brief Message for an actor

import "ignition/msgs/entity.proto";
import "ignition/msgs/header.proto";
import "ignition/msgs/pose.proto";
import "gz/msgs/entity.proto";
import "gz/msgs/header.proto";
import "gz/msgs/pose.proto";

message Actor
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/actuators.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "ActuatorsProtos";
/// \interface Actuators
/// \brief Commands to be sent to the actuator[s].

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

/// \brief Actuator commands.
message Actuators
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/air_pressure_sensor.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AirPressureSensorProtos";
/// \interface AirPressureSensor
/// \brief Definition of an air pressure sensor

import "ignition/msgs/header.proto";
import "ignition/msgs/sensor_noise.proto";
import "gz/msgs/header.proto";
import "gz/msgs/sensor_noise.proto";

/// \brief Message that describes an air pressure sensor.
message AirPressureSensor
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/altimeter.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "AltimeterProtos";
/// \interface Altimeter
/// \brief Data from an altimeter sensor

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

/// \brief Altimeter sensor data
message Altimeter
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/altimeter_sensor.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AltimeterSensorProtos";
/// \interface AltimeterSensor
/// \brief Definition of an altimeter sensor

import "ignition/msgs/header.proto";
import "ignition/msgs/sensor_noise.proto";
import "gz/msgs/header.proto";
import "gz/msgs/sensor_noise.proto";

/// \brief Message that describes an altimeter sensor.
message AltimeterSensor
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/annotated_axis_aligned_2d_box.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AnnotatedAxisAligned2DBoxProtos";
/// \interface AnnotatedAxisAligned2DBox
/// \brief A 2D axis aligned box with label

import "ignition/msgs/header.proto";
import "ignition/msgs/axis_aligned_2d_box.proto";
import "gz/msgs/header.proto";
import "gz/msgs/axis_aligned_2d_box.proto";

message AnnotatedAxisAligned2DBox
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/annotated_axis_aligned_2d_box_v.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AnnotatedAxisAligned2DBox_VProtos";
/// \interface AnnotatedAxisAligned2DBox_V
/// \brief A message for a vector of annotated axis aligned 2d boxes

import "ignition/msgs/header.proto";
import "ignition/msgs/annotated_axis_aligned_2d_box.proto";
import "gz/msgs/header.proto";
import "gz/msgs/annotated_axis_aligned_2d_box.proto";

message AnnotatedAxisAligned2DBox_V
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/annotated_oriented_3d_box.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AnnotatedOriented3DBoxProtos";
/// \interface AnnotatedOriented3DBox
/// \brief A 3D oriented bounding box with label

import "ignition/msgs/header.proto";
import "ignition/msgs/oriented_3d_box.proto";
import "gz/msgs/header.proto";
import "gz/msgs/oriented_3d_box.proto";

message AnnotatedOriented3DBox
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/annotated_oriented_3d_box_v.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AnnotatedOriented3DBox_VProtos";
/// \interface AnnotatedOriented3DBox_V
/// \brief A message for a vector of annotated oriented 3d boxes

import "ignition/msgs/header.proto";
import "ignition/msgs/annotated_oriented_3d_box.proto";
import "gz/msgs/header.proto";
import "gz/msgs/annotated_oriented_3d_box.proto";

message AnnotatedOriented3DBox_V
{
Expand Down
12 changes: 6 additions & 6 deletions proto/gz/msgs/any.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,12 @@ option java_outer_classname = "EmptyProtos";
/// \interface Any
/// \brief A message that is capable of containing a wide variety of data types.

import "ignition/msgs/header.proto";
import "ignition/msgs/color.proto";
import "ignition/msgs/pose.proto";
import "ignition/msgs/quaternion.proto";
import "ignition/msgs/time.proto";
import "ignition/msgs/vector3d.proto";
import "gz/msgs/header.proto";
import "gz/msgs/color.proto";
import "gz/msgs/pose.proto";
import "gz/msgs/quaternion.proto";
import "gz/msgs/time.proto";
import "gz/msgs/vector3d.proto";

message Any
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/atmosphere.proto
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ option java_outer_classname = "AtmosphereProtos";
/// \brief A message containing a description of the global atmosphere
/// properties

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message Atmosphere
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/axis.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AxisProtos";
/// \interface Axis
/// \brief msgs::Joint axis message

import "ignition/msgs/vector3d.proto";
import "ignition/msgs/header.proto";
import "gz/msgs/vector3d.proto";
import "gz/msgs/header.proto";

message Axis
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/axis_aligned_2d_box.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AxisAligned2DBoxProtos";
/// \interface AxisAligned2DBox
/// \brief A 2D axis aligned box

import "ignition/msgs/header.proto";
import "ignition/msgs/vector2d.proto";
import "gz/msgs/header.proto";
import "gz/msgs/vector2d.proto";

message AxisAligned2DBox
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/axis_aligned_box.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "AxisAlignedBoxProtos";
/// \interface AxisAlignedBox
/// \brief An axis aligned box

import "ignition/msgs/header.proto";
import "ignition/msgs/vector3d.proto";
import "gz/msgs/header.proto";
import "gz/msgs/vector3d.proto";

message AxisAlignedBox
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/battery.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "BatteryProtos";
/// \interface Battery
/// \brief Message for a battery

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message Battery
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/battery_state.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "BatteryStateProtos";
/// \interface BatteryState
/// \brief Message for battery state

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message BatteryState
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/boolean.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "BoolProtos";
/// \interface Bool
/// \brief Boolean message

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message Boolean
{
Expand Down
4 changes: 2 additions & 2 deletions proto/gz/msgs/boxgeom.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ option java_outer_classname = "BoxGeomProtos";
/// \interface BoxGeom
/// \brief Information about a box geometry

import "ignition/msgs/header.proto";
import "ignition/msgs/vector3d.proto";
import "gz/msgs/header.proto";
import "gz/msgs/vector3d.proto";

message BoxGeom
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/bytes.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "BytesProtos";
/// \interface Bytes
/// \brief Bytes message

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message Bytes
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/camera_cmd.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "CameraCmdProtos";
/// \interface CameraCmd
/// \brief Message for camera command

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message CameraCmd
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/camera_info.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "CameraInfoProtos";
/// \interface CameraInfo
/// \brief Information about a camera

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

/// \brief Meta information about a camera and the images produced by the
/// camera. This data is typically published alongside a camera image stream
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/camera_lens.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "CameraLensProtos";
/// \interface CameraLens
/// \brief Information and control over a camera lens element

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message CameraLens
{
Expand Down
6 changes: 3 additions & 3 deletions proto/gz/msgs/camerasensor.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ option java_outer_classname = "CameraSensorProtos";
/// \interface CameraSensor
/// \brief Information about a camera sensor element

import "ignition/msgs/vector2d.proto";
import "ignition/msgs/distortion.proto";
import "ignition/msgs/header.proto";
import "gz/msgs/vector2d.proto";
import "gz/msgs/distortion.proto";
import "gz/msgs/header.proto";

message CameraSensor
{
Expand Down
2 changes: 1 addition & 1 deletion proto/gz/msgs/capsulegeom.proto
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ option java_outer_classname = "CapsuleGeomProtos";
/// \interface CapsuleGeom
/// \brief Information about a capsule geometry

import "ignition/msgs/header.proto";
import "gz/msgs/header.proto";

message CapsuleGeom
{
Expand Down
Loading

0 comments on commit 8c77114

Please sign in to comment.