Skip to content

Commit

Permalink
Migrate sources in src, test, examples, and include (#221)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed May 7, 2022
1 parent 6de2850 commit 17c267a
Show file tree
Hide file tree
Showing 36 changed files with 243 additions and 243 deletions.
8 changes: 4 additions & 4 deletions examples/custom_sensor/Odometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@

#include <math.h>

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

#include <ignition/common/Console.hh>
#include <ignition/sensors/Noise.hh>
#include <ignition/sensors/Util.hh>
#include <gz/common/Console.hh>
#include <gz/sensors/Noise.hh>
#include <gz/sensors/Util.hh>

#include "Odometer.hh"

Expand Down
6 changes: 3 additions & 3 deletions examples/custom_sensor/Odometer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@
#ifndef ODOMETER_HH_
#define ODOMETER_HH_

#include <ignition/sensors/Sensor.hh>
#include <ignition/sensors/SensorTypes.hh>
#include <ignition/transport/Node.hh>
#include <gz/sensors/Sensor.hh>
#include <gz/sensors/SensorTypes.hh>
#include <gz/transport/Node.hh>

namespace custom
{
Expand Down
6 changes: 3 additions & 3 deletions examples/imu_noise/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@

#include <sdf/sdf.hh>

#include <ignition/sensors/Noise.hh>
#include <ignition/sensors/GaussianNoiseModel.hh>
#include <ignition/sensors/SensorFactory.hh>
#include <gz/sensors/Noise.hh>
#include <gz/sensors/GaussianNoiseModel.hh>
#include <gz/sensors/SensorFactory.hh>

static constexpr double kSampleFrequency = 100.0;
// 16-bit ADC
Expand Down
8 changes: 4 additions & 4 deletions examples/loop_sensor/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@

#include <sdf/Sensor.hh>

#include <ignition/common/Console.hh>
#include <ignition/common/SignalHandler.hh>
#include <ignition/sensors/Manager.hh>
#include <gz/common/Console.hh>
#include <gz/common/SignalHandler.hh>
#include <gz/sensors/Manager.hh>

// Include all supported sensors
#include <ignition/sensors/AltimeterSensor.hh>
#include <gz/sensors/AltimeterSensor.hh>
#include "../custom_sensor/Odometer.hh"

using namespace std::literals::chrono_literals;
Expand Down
18 changes: 9 additions & 9 deletions examples/save_image/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,26 +21,26 @@
#include <sdf/Noise.hh>
#include <sdf/Sensor.hh>

#include <ignition/common/Image.hh>
#include <ignition/common/Console.hh>
#include <ignition/math/Helpers.hh>
#include <gz/common/Image.hh>
#include <gz/common/Console.hh>
#include <gz/math/Helpers.hh>

// TODO(louise) Remove these pragmas once ign-rendering is disabling the
// warnings
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
#include <ignition/rendering/Material.hh>
#include <ignition/rendering/RenderEngine.hh>
#include <ignition/rendering/RenderingIface.hh>
#include <ignition/rendering/Scene.hh>
#include <ignition/rendering/Visual.hh>
#include <gz/rendering/Material.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
#include <gz/rendering/Scene.hh>
#include <gz/rendering/Visual.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <ignition/sensors.hh>
#include <gz/sensors.hh>

void OnImageFrame(const ignition::msgs::Image &_image)
{
Expand Down
12 changes: 6 additions & 6 deletions include/gz/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,19 @@
* limitations under the License.
*
*/
#ifndef IGNITION_SENSORS_AIRPRESSURESENSOR_HH_
#define IGNITION_SENSORS_AIRPRESSURESENSOR_HH_
#ifndef GZ_SENSORS_AIRPRESSURESENSOR_HH_
#define GZ_SENSORS_AIRPRESSURESENSOR_HH_

#include <memory>

#include <sdf/sdf.hh>

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

#include <ignition/sensors/config.hh>
#include <ignition/sensors/air_pressure/Export.hh>
#include <gz/sensors/config.hh>
#include <gz/sensors/air_pressure/Export.hh>

#include "ignition/sensors/Sensor.hh"
#include "gz/sensors/Sensor.hh"

namespace ignition
{
Expand Down
12 changes: 6 additions & 6 deletions include/gz/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,19 @@
* limitations under the License.
*
*/
#ifndef IGNITION_SENSORS_ALTIMETERSENSOR_HH_
#define IGNITION_SENSORS_ALTIMETERSENSOR_HH_
#ifndef GZ_SENSORS_ALTIMETERSENSOR_HH_
#define GZ_SENSORS_ALTIMETERSENSOR_HH_

#include <memory>

#include <sdf/sdf.hh>

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

#include <ignition/sensors/config.hh>
#include <ignition/sensors/altimeter/Export.hh>
#include <gz/sensors/config.hh>
#include <gz/sensors/altimeter/Export.hh>

#include "ignition/sensors/Sensor.hh"
#include "gz/sensors/Sensor.hh"

namespace ignition
{
Expand Down
14 changes: 7 additions & 7 deletions include/gz/sensors/BrownDistortionModel.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,15 @@
*
*/

#ifndef IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_
#define IGNITION_SENSORS_BROWNDISTORTIONMODEL_HH_
#ifndef GZ_SENSORS_BROWNDISTORTIONMODEL_HH_
#define GZ_SENSORS_BROWNDISTORTIONMODEL_HH_

#include <sdf/sdf.hh>

#include "ignition/sensors/Distortion.hh"
#include "ignition/sensors/Export.hh"
#include "ignition/sensors/config.hh"
#include "ignition/utils/ImplPtr.hh"
#include "gz/sensors/Distortion.hh"
#include "gz/sensors/Export.hh"
#include "gz/sensors/config.hh"
#include "gz/utils/ImplPtr.hh"

namespace ignition
{
Expand All @@ -36,7 +36,7 @@ namespace ignition
class BrownDistortionModelPrivate;

/** \class BrownDistortionModel BrownDistortionModel.hh \
ignition/sensors/BrownDistortionModel.hh
gz/sensors/BrownDistortionModel.hh
**/
/// \brief Brown Distortion Model class
class IGNITION_SENSORS_VISIBLE BrownDistortionModel : public Distortion
Expand Down
18 changes: 9 additions & 9 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,23 +14,23 @@
* limitations under the License.
*
*/
#ifndef IGNITION_SENSORS_CAMERASENSOR_HH_
#define IGNITION_SENSORS_CAMERASENSOR_HH_
#ifndef GZ_SENSORS_CAMERASENSOR_HH_
#define GZ_SENSORS_CAMERASENSOR_HH_

#include <cstdint>
#include <memory>
#include <string>

#include <sdf/sdf.hh>

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

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <ignition/msgs.hh>
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
Expand All @@ -41,15 +41,15 @@
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
#include <ignition/rendering/Camera.hh>
#include <gz/rendering/Camera.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include "ignition/sensors/camera/Export.hh"
#include "ignition/sensors/config.hh"
#include "ignition/sensors/Export.hh"
#include "ignition/sensors/RenderingSensor.hh"
#include "gz/sensors/camera/Export.hh"
#include "gz/sensors/config.hh"
#include "gz/sensors/Export.hh"
#include "gz/sensors/RenderingSensor.hh"

namespace ignition
{
Expand Down
20 changes: 10 additions & 10 deletions include/gz/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,24 +14,24 @@
* limitations under the License.
*
*/
#ifndef IGNITION_SENSORS_DEPTHCAMERASENSOR_HH_
#define IGNITION_SENSORS_DEPTHCAMERASENSOR_HH_
#ifndef GZ_SENSORS_DEPTHCAMERASENSOR_HH_
#define GZ_SENSORS_DEPTHCAMERASENSOR_HH_

#include <memory>
#include <cstdint>
#include <string>

#include <sdf/sdf.hh>

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

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <ignition/msgs.hh>
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
Expand All @@ -42,15 +42,15 @@
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
#include <ignition/rendering/DepthCamera.hh>
#include <gz/rendering/DepthCamera.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include "ignition/sensors/depth_camera/Export.hh"
#include "ignition/sensors/CameraSensor.hh"
#include "ignition/sensors/Export.hh"
#include "ignition/sensors/Sensor.hh"
#include "gz/sensors/depth_camera/Export.hh"
#include "gz/sensors/CameraSensor.hh"
#include "gz/sensors/Export.hh"
#include "gz/sensors/Sensor.hh"

namespace ignition
{
Expand Down
16 changes: 8 additions & 8 deletions include/gz/sensors/Distortion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,17 @@
*
*/

#ifndef IGNITION_SENSORS_DISTORTION_HH_
#define IGNITION_SENSORS_DISTORTION_HH_
#ifndef GZ_SENSORS_DISTORTION_HH_
#define GZ_SENSORS_DISTORTION_HH_

#include <functional>
#include <string>
#include <vector>

#include <ignition/sensors/Export.hh>
#include <ignition/sensors/SensorTypes.hh>
#include <ignition/sensors/config.hh>
#include <ignition/utils/ImplPtr.hh>
#include <gz/sensors/Export.hh>
#include <gz/sensors/SensorTypes.hh>
#include <gz/sensors/config.hh>
#include <gz/utils/ImplPtr.hh>

#include <sdf/sdf.hh>

Expand All @@ -38,7 +38,7 @@ namespace ignition
// Forward declarations
class DistortionPrivate;

/// \class DistortionFactory Distortion.hh ignition/sensors/Distortion.hh
/// \class DistortionFactory Distortion.hh gz/sensors/Distortion.hh
/// \brief Use this distortion manager for creating and loading distortion
/// models.
class IGNITION_SENSORS_VISIBLE DistortionFactory
Expand Down Expand Up @@ -73,7 +73,7 @@ namespace ignition
BROWN = 2
};

/// \class Distortion Distortion.hh ignition/sensors/Distortion.hh
/// \class Distortion Distortion.hh gz/sensors/Distortion.hh
/// \brief Distortion models for sensor output signals.
class IGNITION_SENSORS_VISIBLE Distortion
{
Expand Down
14 changes: 7 additions & 7 deletions include/gz/sensors/ForceTorqueSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,21 +15,21 @@
*
*/

#ifndef IGNITION_SENSORS_FORCETORQUESENSOR_HH_
#define IGNITION_SENSORS_FORCETORQUESENSOR_HH_
#ifndef GZ_SENSORS_FORCETORQUESENSOR_HH_
#define GZ_SENSORS_FORCETORQUESENSOR_HH_

#include <memory>

#include <sdf/sdf.hh>

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

#include <ignition/math/Pose3.hh>
#include <gz/math/Pose3.hh>

#include <ignition/sensors/config.hh>
#include <ignition/sensors/force_torque/Export.hh>
#include <gz/sensors/config.hh>
#include <gz/sensors/force_torque/Export.hh>

#include "ignition/sensors/Sensor.hh"
#include "gz/sensors/Sensor.hh"

namespace ignition
{
Expand Down
12 changes: 6 additions & 6 deletions include/gz/sensors/GaussianNoiseModel.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
*
*/

#ifndef IGNITION_SENSORS_GAUSSIANNOISEMODEL_HH_
#define IGNITION_SENSORS_GAUSSIANNOISEMODEL_HH_
#ifndef GZ_SENSORS_GAUSSIANNOISEMODEL_HH_
#define GZ_SENSORS_GAUSSIANNOISEMODEL_HH_

#include <sdf/sdf.hh>

#include "ignition/sensors/config.hh"
#include "ignition/sensors/Export.hh"
#include "ignition/sensors/Noise.hh"
#include "gz/sensors/config.hh"
#include "gz/sensors/Export.hh"
#include "gz/sensors/Noise.hh"

namespace ignition
{
Expand All @@ -35,7 +35,7 @@ namespace ignition
class GaussianNoiseModelPrivate;

/** \class GaussianNoiseModel GaussianNoiseModel.hh \
ignition/sensors/GaussianNoiseModel.hh
gz/sensors/GaussianNoiseModel.hh
**/
/// \brief Gaussian noise class
class IGNITION_SENSORS_VISIBLE GaussianNoiseModel : public Noise
Expand Down
Loading

0 comments on commit 17c267a

Please sign in to comment.