Skip to content

Commit

Permalink
Use ignition::gazebo:: in class instantiation (#1967)
Browse files Browse the repository at this point in the history
Fixes macOS build.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored May 2, 2023
1 parent 875de1b commit a2a2c85
Show file tree
Hide file tree
Showing 46 changed files with 47 additions and 47 deletions.
2 changes: 1 addition & 1 deletion src/EntityComponentManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
using namespace gz;
using namespace gz::sim;

class gz::sim::EntityComponentManagerPrivate
class ignition::gazebo::EntityComponentManagerPrivate
{
/// \brief Implementation of the CreateEntity function, which takes a specific
/// entity as input.
Expand Down
2 changes: 1 addition & 1 deletion src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include "gz/sim/Link.hh"

class gz::sim::LinkPrivate
class ignition::gazebo::LinkPrivate
{
/// \brief Id of link entity.
public: Entity id{kNullEntity};
Expand Down
2 changes: 1 addition & 1 deletion src/Model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include "gz/sim/components/WindMode.hh"
#include "gz/sim/Model.hh"

class gz::sim::ModelPrivate
class ignition::gazebo::ModelPrivate
{
/// \brief Id of model entity.
public: Entity id{kNullEntity};
Expand Down
2 changes: 1 addition & 1 deletion src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@
#include "gz/sim/components/WindMode.hh"
#include "gz/sim/components/World.hh"

class gz::sim::SdfEntityCreatorPrivate
class ignition::gazebo::SdfEntityCreatorPrivate
{
/// \brief Pointer to entity component manager. We don't assume ownership.
public: EntityComponentManager *ecm{nullptr};
Expand Down
4 changes: 2 additions & 2 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ using namespace gz;
using namespace gz::sim;

/// \brief Private data for PluginInfoConfig.
class gz::sim::ServerConfig::PluginInfoPrivate
class ignition::gazebo::ServerConfig::PluginInfoPrivate
{
/// \brief Default constructor.
public: PluginInfoPrivate() = default;
Expand Down Expand Up @@ -192,7 +192,7 @@ void ServerConfig::PluginInfo::SetSdf(const sdf::ElementPtr &_sdf)
}

/// \brief Private data for ServerConfig.
class gz::sim::ServerConfigPrivate
class ignition::gazebo::ServerConfigPrivate
{
/// \brief Default constructor.
public: ServerConfigPrivate()
Expand Down
2 changes: 1 addition & 1 deletion src/SystemLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

using namespace gz::sim;

class gz::sim::SystemLoaderPrivate
class ignition::gazebo::SystemLoaderPrivate
{
//////////////////////////////////////////////////
public: explicit SystemLoaderPrivate() = default;
Expand Down
2 changes: 1 addition & 1 deletion src/TestFixture.cc
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ void HelperSystem::PostUpdate(const UpdateInfo &_info,
}

//////////////////////////////////////////////////
class gz::sim::TestFixturePrivate
class ignition::gazebo::TestFixturePrivate
{
/// \brief Initialize fixture
/// \param[in] _config Server config
Expand Down
2 changes: 1 addition & 1 deletion src/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include "gz/sim/components/World.hh"
#include "gz/sim/World.hh"

class gz::sim::WorldPrivate
class ignition::gazebo::WorldPrivate
{
/// \brief Id of world entity.
public: Entity id{kNullEntity};
Expand Down
2 changes: 1 addition & 1 deletion src/rendering/MarkerManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ using namespace gz;
using namespace gz::sim;

/// Private data for the MarkerManager class
class gz::sim::MarkerManagerPrivate
class ignition::gazebo::MarkerManagerPrivate
{
/// \brief Processes a marker message.
/// \param[in] _msg The message data.
Expand Down
2 changes: 1 addition & 1 deletion src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ using namespace gz;
using namespace gz::sim;

// Private data class.
class gz::sim::RenderUtilPrivate
class ignition::gazebo::RenderUtilPrivate
{
/// True if the rendering component is initialized
public: bool initialized = false;
Expand Down
2 changes: 1 addition & 1 deletion src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ using namespace gz::sim;
using namespace std::chrono_literals;

/// \brief Private data class.
class gz::sim::SceneManagerPrivate
class ignition::gazebo::SceneManagerPrivate
{
/// \brief Keep track of world ID, which is equivalent to the scene's
/// root visual.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/ackermann_steering/AckermannSteering.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ struct Commands
Commands() : lin(0.0), ang(0.0) {}
};

class gz::sim::systems::AckermannSteeringPrivate
class ignition::gazebo::systems::AckermannSteeringPrivate
{
/// \brief Callback for velocity subscription
/// \param[in] _msg Velocity message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/air_pressure/AirPressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private AirPressure data class.
class gz::sim::systems::AirPressurePrivate
class ignition::gazebo::systems::AirPressurePrivate
{
/// \brief A map of air pressure entity to its sensor
public: std::unordered_map<Entity,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/altimeter/Altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private Altimeter data class.
class gz::sim::systems::AltimeterPrivate
class ignition::gazebo::systems::AltimeterPrivate
{
/// \brief A map of altimeter entity to its sensor
public: std::unordered_map<Entity,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/apply_joint_force/ApplyJointForce.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::ApplyJointForcePrivate
class ignition::gazebo::systems::ApplyJointForcePrivate
{
/// \brief Callback for joint force subscription
/// \param[in] _msg Joint force message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/apply_link_wrench/ApplyLinkWrench.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::ApplyLinkWrenchPrivate
class ignition::gazebo::systems::ApplyLinkWrenchPrivate
{
/// \brief Callback for wrench subscription
/// \param[in] _msg Wrench message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/battery_plugin/LinearBatteryPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::LinearBatteryPluginPrivate
class ignition::gazebo::systems::LinearBatteryPluginPrivate
{
/// \brief Reset the plugin
public: void Reset();
Expand Down
2 changes: 1 addition & 1 deletion src/systems/buoyancy/Buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::BuoyancyPrivate
class ignition::gazebo::systems::BuoyancyPrivate
{
/// \brief Get the fluid density based on a pose. This function can be
/// used to adjust the fluid density based on the pose of an object in the
Expand Down
2 changes: 1 addition & 1 deletion src/systems/camera_video_recorder/CameraVideoRecorder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ using namespace gz::sim;
using namespace systems;

// Private data class.
class gz::sim::systems::CameraVideoRecorderPrivate
class ignition::gazebo::systems::CameraVideoRecorderPrivate
{
/// \brief Callback for the video recorder service
public: bool OnRecordVideo(const msgs::VideoRecord &_msg,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ using namespace gz::sim;
using namespace systems;


class gz::sim::systems::ColladaWorldExporterPrivate
class ignition::gazebo::systems::ColladaWorldExporterPrivate
{
// Default constructor
public: ColladaWorldExporterPrivate() = default;
Expand Down
2 changes: 1 addition & 1 deletion src/systems/contact/Contact.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class ContactSensor
public: std::vector<Entity> collisionEntities;
};

class gz::sim::systems::ContactPrivate
class ignition::gazebo::systems::ContactPrivate
{
/// \brief Create sensors that correspond to entities in the simulation
/// \param[in] _ecm Mutable reference to ECM.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/diff_drive/DiffDrive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ struct Commands
Commands() : lin(0.0), ang(0.0) {}
};

class gz::sim::systems::DiffDrivePrivate
class ignition::gazebo::systems::DiffDrivePrivate
{
/// \brief Callback for velocity subscription
/// \param[in] _msg Velocity message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/imu/Imu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private Imu data class.
class gz::sim::systems::ImuPrivate
class ignition::gazebo::systems::ImuPrivate
{
/// \brief A map of IMU entity to its IMU sensor.
public: std::unordered_map<Entity,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/joint_controller/JointController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::JointControllerPrivate
class ignition::gazebo::systems::JointControllerPrivate
{
/// \brief Callback for velocity subscription
/// \param[in] _msg Velocity message
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::JointPositionControllerPrivate
class ignition::gazebo::systems::JointPositionControllerPrivate
{
/// \brief Callback for position subscription
/// \param[in] _msg Position message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/kinetic_energy_monitor/KineticEnergyMonitor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private data class
class gz::sim::systems::KineticEnergyMonitorPrivate
class ignition::gazebo::systems::KineticEnergyMonitorPrivate
{
/// \brief Link of the model.
public: Entity linkEntity;
Expand Down
2 changes: 1 addition & 1 deletion src/systems/lift_drag/LiftDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::LiftDragPrivate
class ignition::gazebo::systems::LiftDragPrivate
{
// Initialize the system
public: void Load(const EntityComponentManager &_ecm,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/log/LogPlayback.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private LogPlayback data class.
class gz::sim::systems::LogPlaybackPrivate
class ignition::gazebo::systems::LogPlaybackPrivate
{
/// \brief Extract model resource files and state file from compression.
/// \return True if extraction was successful.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/log/LogRecord.cc
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ using namespace gz;
using namespace ignition::gazebo::systems;

// Private data class.
class gz::sim::systems::LogRecordPrivate
class ignition::gazebo::systems::LogRecordPrivate
{
/// \brief Start recording
/// \param[in] _logPath Path to record to.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/log_video_recorder/LogVideoRecorder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ using namespace gz::sim;
using namespace systems;

// Private data class.
class gz::sim::systems::LogVideoRecorderPrivate
class ignition::gazebo::systems::LogVideoRecorderPrivate
{
/// \brief Rewind the log
public: void Rewind();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::LogicalAudioSensorPluginPrivate
class ignition::gazebo::systems::LogicalAudioSensorPluginPrivate
{
/// \brief Creates an audio source with attributes specified in an SDF file.
/// \param[in] _elem A pointer to the source element in the SDF file.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/logical_camera/LogicalCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private LogicalCamera data class.
class gz::sim::systems::LogicalCameraPrivate
class ignition::gazebo::systems::LogicalCameraPrivate
{
/// \brief A map of logicalCamera entities
public: std::unordered_map<Entity,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/magnetometer/Magnetometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private Magnetometer data class.
class gz::sim::systems::MagnetometerPrivate
class ignition::gazebo::systems::MagnetometerPrivate
{
/// \brief A map of magnetometer entity to its sensor.
public: std::unordered_map<Entity,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ enum class MotorType {
kForce
};

class gz::sim::systems::MulticopterMotorModelPrivate
class ignition::gazebo::systems::MulticopterMotorModelPrivate
{
/// \brief Callback for actuator commands.
public: void OnActuatorMsg(const msgs::Actuators &_msg);
Expand Down
2 changes: 1 addition & 1 deletion src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ namespace components = gz::sim::components;


// Private data class.
class gz::sim::systems::PhysicsPrivate
class ignition::gazebo::systems::PhysicsPrivate
{
/// \brief This is the minimum set of features that any physics engine must
/// implement to be supported by this system.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/pose_publisher/PosePublisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private data class for PosePublisher
class gz::sim::systems::PosePublisherPrivate
class ignition::gazebo::systems::PosePublisherPrivate
{
/// \brief Initializes internal caches for entities whose poses are to be
/// published and their names
Expand Down
2 changes: 1 addition & 1 deletion src/systems/scene_broadcaster/SceneBroadcaster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ using namespace gz::sim;
using namespace systems;

// Private data class.
class gz::sim::systems::SceneBroadcasterPrivate
class ignition::gazebo::systems::SceneBroadcasterPrivate
{
/// \brief Type alias for the graph used to represent the scene graph.
public: using SceneGraphType = math::graph::DirectedGraph<
Expand Down
2 changes: 1 addition & 1 deletion src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ using namespace gz::sim;
using namespace systems;

// Private data class.
class gz::sim::systems::SensorsPrivate
class ignition::gazebo::systems::SensorsPrivate
{
/// \brief Sensor manager object. This manages the lifecycle of the
/// instantiated sensors.
Expand Down
2 changes: 1 addition & 1 deletion src/systems/thermal/Thermal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ using namespace gz::sim;
using namespace systems;

/// \brief Private Thermal data class.
class gz::sim::systems::ThermalPrivate
class ignition::gazebo::systems::ThermalPrivate
{
};

Expand Down
2 changes: 1 addition & 1 deletion src/systems/touch_plugin/TouchPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::TouchPluginPrivate
class ignition::gazebo::systems::TouchPluginPrivate
{
// Initialize the plugin
public: void Load(const EntityComponentManager &_ecm,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/track_controller/TrackController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ using namespace gz;
using namespace gz::sim;
using namespace systems;

class gz::sim::systems::TrackControllerPrivate
class ignition::gazebo::systems::TrackControllerPrivate
{
public : ~TrackControllerPrivate() {}
/// \brief Register a collision entity to work with this system (e.g. enable
Expand Down
2 changes: 1 addition & 1 deletion src/systems/tracked_vehicle/TrackedVehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ struct Commands
Commands() {}
};

class gz::sim::systems::TrackedVehiclePrivate
class ignition::gazebo::systems::TrackedVehiclePrivate
{
/// \brief Callback for velocity subscription
/// \param[in] _msg Velocity message
Expand Down
2 changes: 1 addition & 1 deletion src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ class PhysicsCommand : public UserCommandBase
}

/// \brief Private UserCommands data class.
class gz::sim::systems::UserCommandsPrivate
class ignition::gazebo::systems::UserCommandsPrivate
{
/// \brief Callback for create service
/// \param[in] _req Request containing entity description.
Expand Down
Loading

0 comments on commit a2a2c85

Please sign in to comment.