diff --git a/examples/custom_scene_viewer/ManualSceneDemo.hh b/examples/custom_scene_viewer/ManualSceneDemo.hh index 766a9ad19..cee290d1b 100644 --- a/examples/custom_scene_viewer/ManualSceneDemo.hh +++ b/examples/custom_scene_viewer/ManualSceneDemo.hh @@ -21,7 +21,7 @@ #include #include "TestTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/examples/custom_scene_viewer/SceneBuilder.hh b/examples/custom_scene_viewer/SceneBuilder.hh index 8674336fa..42362ccd9 100644 --- a/examples/custom_scene_viewer/SceneBuilder.hh +++ b/examples/custom_scene_viewer/SceneBuilder.hh @@ -20,7 +20,7 @@ #include #include "TestTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/examples/custom_scene_viewer/TestTypes.hh b/examples/custom_scene_viewer/TestTypes.hh index 020cbb40c..41e1dd3ed 100644 --- a/examples/custom_scene_viewer/TestTypes.hh +++ b/examples/custom_scene_viewer/TestTypes.hh @@ -20,7 +20,7 @@ #include #include -namespace gz +namespace ignition { namespace rendering { diff --git a/examples/gazebo_scene_viewer/CameraWindow.hh b/examples/gazebo_scene_viewer/CameraWindow.hh index 0ed0bb3e4..e554bc0c8 100644 --- a/examples/gazebo_scene_viewer/CameraWindow.hh +++ b/examples/gazebo_scene_viewer/CameraWindow.hh @@ -20,8 +20,6 @@ #include #include "gz/rendering/RenderTypes.hh" -namespace gz = gz::rendering; - void GlutRun(std::vector _cameras); void GlutDisplay(); diff --git a/examples/gazebo_scene_viewer/GazeboDemo.cc b/examples/gazebo_scene_viewer/GazeboDemo.cc index 06d613a4c..14b3bace6 100644 --- a/examples/gazebo_scene_viewer/GazeboDemo.cc +++ b/examples/gazebo_scene_viewer/GazeboDemo.cc @@ -28,9 +28,9 @@ using namespace rendering; void Connect() { - sim::common::Console::SetQuiet(false); - sim::transport::init(); - sim::transport::run(); + gazebo::common::Console::SetQuiet(false); + gazebo::transport::init(); + gazebo::transport::run(); SceneManager* manager = SceneManager::Instance(); manager->Load(); diff --git a/examples/gazebo_scene_viewer/GazeboWorldDemo.cc b/examples/gazebo_scene_viewer/GazeboWorldDemo.cc index 57a758095..253ffde48 100644 --- a/examples/gazebo_scene_viewer/GazeboWorldDemo.cc +++ b/examples/gazebo_scene_viewer/GazeboWorldDemo.cc @@ -29,8 +29,8 @@ using namespace rendering; void Connect() { common::Console::SetVerbosity(4); - sim::transport::init(); - sim::transport::run(); + gazebo::transport::init(); + gazebo::transport::run(); SceneManager* manager = SceneManager::Instance(); manager->Load(); diff --git a/examples/gazebo_scene_viewer/SceneManager.cc b/examples/gazebo_scene_viewer/SceneManager.cc index 3c603583a..5e7fc7f15 100644 --- a/examples/gazebo_scene_viewer/SceneManager.cc +++ b/examples/gazebo_scene_viewer/SceneManager.cc @@ -166,17 +166,17 @@ void SceneManagerPrivate::Load() void SceneManagerPrivate::Init() { // listen for pre-render events - this->preRenderConn = sim::event::Events::ConnectPreRender( + this->preRenderConn = gazebo::event::Events::ConnectPreRender( std::bind(&SceneManagerPrivate::UpdateScenes, this)); // setup transport communication node - this->transportNode = sim::transport::NodePtr( - new sim::transport::Node()); + this->transportNode = gazebo::transport::NodePtr( + new gazebo::transport::Node()); this->transportNode->Init(); // create publisher for sending scene request this->requestPub = - this->transportNode->Advertise("~/request"); + this->transportNode->Advertise("~/request"); // listen for deletion requests this->requestSub = this->transportNode->Subscribe("~/request", @@ -364,7 +364,7 @@ void SceneManagerPrivate::UpdateScenes() ////////////////////////////////////////////////// void SceneManagerPrivate::SendSceneRequest() { - sim::msgs::Request *request = sim::msgs::CreateRequest("scene_info"); + gazebo::msgs::Request *request = gazebo::msgs::CreateRequest("scene_info"); this->sceneRequestId = request->id(); this->requestPub->Publish(*request); } @@ -871,33 +871,33 @@ void SubSceneManager::ClearMessages() } ////////////////////////////////////////////////// -void SubSceneManager::ProcessLight(const sim::msgs::Light &_lightMsg) +void SubSceneManager::ProcessLight(const gazebo::msgs::Light &_lightMsg) { // TODO(anyone): get parent when protobuf message is updated this->ProcessLight(_lightMsg, this->activeScene->RootVisual()); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessLight(const sim::msgs::Light &_lightMsg, +void SubSceneManager::ProcessLight(const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { // check if type specified if (_lightMsg.has_type()) { - sim::msgs::Light::LightType type = _lightMsg.type(); + gazebo::msgs::Light::LightType type = _lightMsg.type(); // determine light type switch (_lightMsg.type()) { - case sim::msgs::Light::POINT: + case gazebo::msgs::Light::POINT: this->ProcessPointLight(_lightMsg, _parent); return; - case sim::msgs::Light::SPOT: + case gazebo::msgs::Light::SPOT: this->ProcessSpotLight(_lightMsg, _parent); return; - case sim::msgs::Light::DIRECTIONAL: + case gazebo::msgs::Light::DIRECTIONAL: this->ProcessDirectionalLight(_lightMsg, _parent); return; @@ -915,7 +915,7 @@ void SubSceneManager::ProcessLight(const sim::msgs::Light &_lightMsg, ////////////////////////////////////////////////// void SubSceneManager::ProcessDirectionalLight( - const sim::msgs::Light &_lightMsg, VisualPtr _parent) + const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { DirectionalLightPtr light = this->DirectionalLight(_lightMsg, _parent); if (light) this->ProcessDirectionalLightImpl(_lightMsg, light); @@ -923,12 +923,12 @@ void SubSceneManager::ProcessDirectionalLight( ////////////////////////////////////////////////// void SubSceneManager::ProcessDirectionalLightImpl( - const sim::msgs::Light &_lightMsg, DirectionalLightPtr _light) + const gazebo::msgs::Light &_lightMsg, DirectionalLightPtr _light) { // set direction if available if (_lightMsg.has_direction()) { - const sim::msgs::Vector3d &dirMsg = _lightMsg.direction(); + const gazebo::msgs::Vector3d &dirMsg = _lightMsg.direction(); _light->SetDirection(SubSceneManager::Convert(dirMsg)); } @@ -938,7 +938,7 @@ void SubSceneManager::ProcessDirectionalLightImpl( ////////////////////////////////////////////////// DirectionalLightPtr SubSceneManager::DirectionalLight( - const sim::msgs::Light &_lightMsg, VisualPtr _parent) + const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { // find existing light with name std::string name = _lightMsg.name(); @@ -959,14 +959,14 @@ DirectionalLightPtr SubSceneManager::DirectionalLight( ////////////////////////////////////////////////// DirectionalLightPtr SubSceneManager::CreateDirectionalLight( - const sim::msgs::Light &_lightMsg) + const gazebo::msgs::Light &_lightMsg) { std::string name = _lightMsg.name(); return this->activeScene->CreateDirectionalLight(name); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessPointLight(const sim::msgs::Light &_lightMsg, +void SubSceneManager::ProcessPointLight(const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { PointLightPtr light = this->PointLight(_lightMsg, _parent); @@ -975,7 +975,7 @@ void SubSceneManager::ProcessPointLight(const sim::msgs::Light &_lightMsg, ////////////////////////////////////////////////// void SubSceneManager::ProcessPointLightImpl( - const sim::msgs::Light &_lightMsg, PointLightPtr _light) + const gazebo::msgs::Light &_lightMsg, PointLightPtr _light) { // process general light information this->ProcessLightImpl(_lightMsg, _light); @@ -983,7 +983,7 @@ void SubSceneManager::ProcessPointLightImpl( ////////////////////////////////////////////////// PointLightPtr SubSceneManager::PointLight( - const sim::msgs::Light &_lightMsg, VisualPtr _parent) + const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { // find existing light with name std::string name = _lightMsg.name(); @@ -1003,14 +1003,14 @@ PointLightPtr SubSceneManager::PointLight( ////////////////////////////////////////////////// PointLightPtr SubSceneManager::CreatePointLight( - const sim::msgs::Light &_lightMsg) + const gazebo::msgs::Light &_lightMsg) { std::string name = _lightMsg.name(); return this->activeScene->CreatePointLight(name); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessSpotLight(const sim::msgs::Light &_lightMsg, +void SubSceneManager::ProcessSpotLight(const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { SpotLightPtr light = this->SpotLight(_lightMsg, _parent); @@ -1019,12 +1019,12 @@ void SubSceneManager::ProcessSpotLight(const sim::msgs::Light &_lightMsg, ////////////////////////////////////////////////// void SubSceneManager::ProcessSpotLightImpl( - const sim::msgs::Light &_lightMsg, SpotLightPtr _light) + const gazebo::msgs::Light &_lightMsg, SpotLightPtr _light) { // set direction if available if (_lightMsg.has_direction()) { - const sim::msgs::Vector3d &dirMsg = _lightMsg.direction(); + const gazebo::msgs::Vector3d &dirMsg = _lightMsg.direction(); _light->SetDirection(SubSceneManager::Convert(dirMsg)); } @@ -1054,7 +1054,7 @@ void SubSceneManager::ProcessSpotLightImpl( } ////////////////////////////////////////////////// -SpotLightPtr SubSceneManager::SpotLight(const sim::msgs::Light &_lightMsg, +SpotLightPtr SubSceneManager::SpotLight(const gazebo::msgs::Light &_lightMsg, VisualPtr _parent) { // find existing light with name @@ -1075,14 +1075,14 @@ SpotLightPtr SubSceneManager::SpotLight(const sim::msgs::Light &_lightMsg, ////////////////////////////////////////////////// SpotLightPtr SubSceneManager::CreateSpotLight( - const sim::msgs::Light &_lightMsg) + const gazebo::msgs::Light &_lightMsg) { std::string name = _lightMsg.name(); return this->activeScene->CreateSpotLight(name); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessLightImpl(const sim::msgs::Light &_lightMsg, +void SubSceneManager::ProcessLightImpl(const gazebo::msgs::Light &_lightMsg, LightPtr _light) { // set pose if available @@ -1094,14 +1094,14 @@ void SubSceneManager::ProcessLightImpl(const sim::msgs::Light &_lightMsg, // set diffuse if available if (_lightMsg.has_diffuse()) { - const sim::msgs::Color &colorMsg = _lightMsg.diffuse(); + const gazebo::msgs::Color &colorMsg = _lightMsg.diffuse(); _light->SetDiffuseColor(SubSceneManager::Convert(colorMsg)); } // set specular if available if (_lightMsg.has_specular()) { - const sim::msgs::Color &colorMsg = _lightMsg.specular(); + const gazebo::msgs::Color &colorMsg = _lightMsg.specular(); _light->SetSpecularColor(SubSceneManager::Convert(colorMsg)); } @@ -1142,14 +1142,14 @@ void SubSceneManager::ProcessLightImpl(const sim::msgs::Light &_lightMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessSensor(const sim::msgs::Sensor &_sensorMsg) +void SubSceneManager::ProcessSensor(const gazebo::msgs::Sensor &_sensorMsg) { VisualPtr parent = this->Parent(_sensorMsg.parent()); this->ProcessSensor(_sensorMsg, parent); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessSensor(const sim::msgs::Sensor &_sensorMsg, +void SubSceneManager::ProcessSensor(const gazebo::msgs::Sensor &_sensorMsg, VisualPtr _parent) { // TODO(anyone): process all types @@ -1161,7 +1161,7 @@ void SubSceneManager::ProcessSensor(const sim::msgs::Sensor &_sensorMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessCamera(const sim::msgs::Sensor &_sensorMsg, +void SubSceneManager::ProcessCamera(const gazebo::msgs::Sensor &_sensorMsg, VisualPtr _parent) { CameraPtr camera = this->Camera(_sensorMsg, _parent); @@ -1170,7 +1170,7 @@ void SubSceneManager::ProcessCamera(const sim::msgs::Sensor &_sensorMsg, } ////////////////////////////////////////////////// -CameraPtr SubSceneManager::Camera(const sim::msgs::Sensor &_sensorMsg, +CameraPtr SubSceneManager::Camera(const gazebo::msgs::Sensor &_sensorMsg, VisualPtr _parent) { // find existing camera with name @@ -1189,7 +1189,7 @@ CameraPtr SubSceneManager::Camera(const sim::msgs::Sensor &_sensorMsg, } ////////////////////////////////////////////////// -CameraPtr SubSceneManager::CreateCamera(const sim::msgs::Sensor &_sensorMsg) +CameraPtr SubSceneManager::CreateCamera(const gazebo::msgs::Sensor &_sensorMsg) { bool hasId = _sensorMsg.has_id(); unsigned int id = _sensorMsg.id(); @@ -1201,14 +1201,14 @@ CameraPtr SubSceneManager::CreateCamera(const sim::msgs::Sensor &_sensorMsg) } ////////////////////////////////////////////////// -void SubSceneManager::ProcessModel(const sim::msgs::Model &_modelMsg) +void SubSceneManager::ProcessModel(const gazebo::msgs::Model &_modelMsg) { VisualPtr parent = this->activeScene->RootVisual(); this->ProcessModel(_modelMsg, parent); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessModel(const sim::msgs::Model &_modelMsg, +void SubSceneManager::ProcessModel(const gazebo::msgs::Model &_modelMsg, VisualPtr _parent) { VisualPtr model = this->Model(_modelMsg, _parent); @@ -1228,14 +1228,14 @@ void SubSceneManager::ProcessModel(const sim::msgs::Model &_modelMsg, // process each sensor in joint for (int i = 0; i < _modelMsg.joint_size(); ++i) { - const sim::msgs::Joint &joint = _modelMsg.joint(i); + const gazebo::msgs::Joint &joint = _modelMsg.joint(i); this->ProcessJoint(joint, model); } // process each sensor in link for (int i = 0; i < _modelMsg.link_size(); ++i) { - const sim::msgs::Link &link = _modelMsg.link(i); + const gazebo::msgs::Link &link = _modelMsg.link(i); this->ProcessLink(link, model); } @@ -1243,13 +1243,13 @@ void SubSceneManager::ProcessModel(const sim::msgs::Model &_modelMsg, // always skip first empty visual for (int i = 1; i < _modelMsg.visual_size(); ++i) { - const sim::msgs::Visual &visual = _modelMsg.visual(i); + const gazebo::msgs::Visual &visual = _modelMsg.visual(i); this->ProcessVisual(visual, model); } } ////////////////////////////////////////////////// -VisualPtr SubSceneManager::Model(const sim::msgs::Model &_modelMsg, +VisualPtr SubSceneManager::Model(const gazebo::msgs::Model &_modelMsg, VisualPtr _parent) { bool hasId = _modelMsg.has_id(); @@ -1259,14 +1259,14 @@ VisualPtr SubSceneManager::Model(const sim::msgs::Model &_modelMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessJoint(const sim::msgs::Joint &_jointMsg) +void SubSceneManager::ProcessJoint(const gazebo::msgs::Joint &_jointMsg) { VisualPtr parent = this->Parent(_jointMsg.parent()); this->ProcessJoint(_jointMsg, parent); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessJoint(const sim::msgs::Joint &_jointMsg, +void SubSceneManager::ProcessJoint(const gazebo::msgs::Joint &_jointMsg, VisualPtr _parent) { VisualPtr joint = this->Joint(_jointMsg, _parent); @@ -1280,13 +1280,13 @@ void SubSceneManager::ProcessJoint(const sim::msgs::Joint &_jointMsg, // process each sensor in joint for (int i = 0; i < _jointMsg.sensor_size(); ++i) { - const sim::msgs::Sensor &sensor = _jointMsg.sensor(i); + const gazebo::msgs::Sensor &sensor = _jointMsg.sensor(i); this->ProcessSensor(sensor, joint); } } ////////////////////////////////////////////////// -VisualPtr SubSceneManager::Joint(const sim::msgs::Joint &_jointMsg, +VisualPtr SubSceneManager::Joint(const gazebo::msgs::Joint &_jointMsg, VisualPtr _parent) { bool hasId = _jointMsg.has_id(); @@ -1296,14 +1296,14 @@ VisualPtr SubSceneManager::Joint(const sim::msgs::Joint &_jointMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessVisual(const sim::msgs::Visual &_visualMsg) +void SubSceneManager::ProcessVisual(const gazebo::msgs::Visual &_visualMsg) { VisualPtr parent = this->Parent(_visualMsg.parent_name()); this->ProcessVisual(_visualMsg, parent); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessVisual(const sim::msgs::Visual &_visualMsg, +void SubSceneManager::ProcessVisual(const gazebo::msgs::Visual &_visualMsg, VisualPtr _parent) { VisualPtr visual = this->Visual(_visualMsg, _parent); @@ -1333,14 +1333,14 @@ void SubSceneManager::ProcessVisual(const sim::msgs::Visual &_visualMsg, // set material if available if (_visualMsg.has_material()) { - const sim::msgs::Material matMsg = _visualMsg.material(); + const gazebo::msgs::Material matMsg = _visualMsg.material(); MaterialPtr material = this->CreateMaterial(matMsg); visual->SetMaterial(material); } } ////////////////////////////////////////////////// -VisualPtr SubSceneManager::Visual(const sim::msgs::Visual &_visualMsg, +VisualPtr SubSceneManager::Visual(const gazebo::msgs::Visual &_visualMsg, VisualPtr _parent) { bool hasId = _visualMsg.has_id(); @@ -1350,7 +1350,7 @@ VisualPtr SubSceneManager::Visual(const sim::msgs::Visual &_visualMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessLink(const sim::msgs::Link &_linkMsg, +void SubSceneManager::ProcessLink(const gazebo::msgs::Link &_linkMsg, VisualPtr _parent) { VisualPtr link = this->Link(_linkMsg, _parent); @@ -1365,20 +1365,20 @@ void SubSceneManager::ProcessLink(const sim::msgs::Link &_linkMsg, // always skip first empty visual for (int i = 1; i < _linkMsg.visual_size(); ++i) { - const sim::msgs::Visual &visual = _linkMsg.visual(i); + const gazebo::msgs::Visual &visual = _linkMsg.visual(i); this->ProcessVisual(visual, link); } // process each sensor in link for (int i = 0; i < _linkMsg.sensor_size(); ++i) { - const sim::msgs::Sensor &sensor = _linkMsg.sensor(i); + const gazebo::msgs::Sensor &sensor = _linkMsg.sensor(i); this->ProcessSensor(sensor, link); } } ////////////////////////////////////////////////// -VisualPtr SubSceneManager::Link(const sim::msgs::Link &_linkMsg, +VisualPtr SubSceneManager::Link(const gazebo::msgs::Link &_linkMsg, VisualPtr _parent) { bool hasId = _linkMsg.has_id(); @@ -1415,7 +1415,7 @@ VisualPtr SubSceneManager::CreateVisual(bool _hasId, unsigned int _id, ////////////////////////////////////////////////// void SubSceneManager::ProcessGeometry( - const sim::msgs::Geometry &_geometryMsg, VisualPtr _parent) + const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { GeomType geomType = _geometryMsg.type(); GeomFunc geomFunc = this->geomFunctions[geomType]; @@ -1426,30 +1426,30 @@ void SubSceneManager::ProcessGeometry( { ignerr << "Unsupported geometry type: " << geomType << std::endl; ignwarn << "Using empty geometry instead" << std::endl; - geomFunc = this->geomFunctions[sim::msgs::Geometry::EMPTY]; + geomFunc = this->geomFunctions[gazebo::msgs::Geometry::EMPTY]; } (this->*geomFunc)(_geometryMsg, _parent); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessBox(const sim::msgs::Geometry &_geometryMsg, +void SubSceneManager::ProcessBox(const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { GeometryPtr box = this->activeScene->CreateBox(); - const sim::msgs::BoxGeom &boxMsg = _geometryMsg.box(); - const sim::msgs::Vector3d sizeMsg = boxMsg.size(); + const gazebo::msgs::BoxGeom &boxMsg = _geometryMsg.box(); + const gazebo::msgs::Vector3d sizeMsg = boxMsg.size(); _parent->SetLocalScale(SubSceneManager::Convert(sizeMsg)); _parent->AddGeometry(box); } ////////////////////////////////////////////////// void SubSceneManager::ProcessCone( - const sim::msgs::Geometry &/*_geometryMsg*/, VisualPtr _parent) + const gazebo::msgs::Geometry &/*_geometryMsg*/, VisualPtr _parent) { // TODO(anyone): needs protobuf msg GeometryPtr cone = this->activeScene->CreateCone(); - // const sim::msgs::ConeGeom &coneMsg = _geometryMsg.cone(); + // const gazebo::msgs::ConeGeom &coneMsg = _geometryMsg.cone(); // double x = coneMsg.radius(); // double y = coneMsg.radius(); // double z = coneMsg.length(); @@ -1459,10 +1459,10 @@ void SubSceneManager::ProcessCone( ////////////////////////////////////////////////// void SubSceneManager::ProcessCylinder( - const sim::msgs::Geometry &_geometryMsg, VisualPtr _parent) + const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { GeometryPtr cylinder = this->activeScene->CreateCylinder(); - const sim::msgs::CylinderGeom &cylinderMsg = _geometryMsg.cylinder(); + const gazebo::msgs::CylinderGeom &cylinderMsg = _geometryMsg.cylinder(); double x = 2 * cylinderMsg.radius(); double y = 2 * cylinderMsg.radius(); double z = cylinderMsg.length(); @@ -1471,16 +1471,16 @@ void SubSceneManager::ProcessCylinder( } ////////////////////////////////////////////////// -void SubSceneManager::ProcessEmpty(const sim::msgs::Geometry&, VisualPtr) +void SubSceneManager::ProcessEmpty(const gazebo::msgs::Geometry&, VisualPtr) { // do nothing } ////////////////////////////////////////////////// -void SubSceneManager::ProcessMesh(const sim::msgs::Geometry &_geometryMsg, +void SubSceneManager::ProcessMesh(const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { - const sim::msgs::MeshGeom &meshMsg = _geometryMsg.mesh(); + const gazebo::msgs::MeshGeom &meshMsg = _geometryMsg.mesh(); // if the model contains model:// try to find the meshes in ~/.gazebo std::list modelPaths; @@ -1537,7 +1537,7 @@ void SubSceneManager::ProcessMesh(const sim::msgs::Geometry &_geometryMsg, // set scale if available if (meshMsg.has_scale()) { - const sim::msgs::Vector3d scaleMsg = meshMsg.scale(); + const gazebo::msgs::Vector3d scaleMsg = meshMsg.scale(); _parent->SetLocalScale(SubSceneManager::Convert(scaleMsg)); } @@ -1546,30 +1546,30 @@ void SubSceneManager::ProcessMesh(const sim::msgs::Geometry &_geometryMsg, } ////////////////////////////////////////////////// -void SubSceneManager::ProcessPlane(const sim::msgs::Geometry &_geometryMsg, +void SubSceneManager::ProcessPlane(const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { // TODO(anyone): handle plane normal GeometryPtr plane = this->activeScene->CreatePlane(); - const sim::msgs::PlaneGeom &planeMsg = _geometryMsg.plane(); - const sim::msgs::Vector2d planeSize = planeMsg.size(); + const gazebo::msgs::PlaneGeom &planeMsg = _geometryMsg.plane(); + const gazebo::msgs::Vector2d planeSize = planeMsg.size(); _parent->SetLocalScale(planeSize.x(), planeSize.y(), 1); _parent->AddGeometry(plane); } ////////////////////////////////////////////////// -void SubSceneManager::ProcessSphere(const sim::msgs::Geometry &_geometryMsg, +void SubSceneManager::ProcessSphere(const gazebo::msgs::Geometry &_geometryMsg, VisualPtr _parent) { GeometryPtr sphere = this->activeScene->CreateSphere(); - const sim::msgs::SphereGeom &sphereMsg = _geometryMsg.sphere(); + const gazebo::msgs::SphereGeom &sphereMsg = _geometryMsg.sphere(); _parent->SetLocalScale(2 * sphereMsg.radius()); _parent->AddGeometry(sphere); } ////////////////////////////////////////////////// MaterialPtr SubSceneManager::CreateMaterial( - const sim::msgs::Material &_materialMsg) + const gazebo::msgs::Material &_materialMsg) { MaterialPtr material = this->activeScene->CreateMaterial(); @@ -1580,7 +1580,7 @@ MaterialPtr SubSceneManager::CreateMaterial( // set ambient if available if (_materialMsg.has_ambient()) { - sim::msgs::Color msg = _materialMsg.ambient(); + gazebo::msgs::Color msg = _materialMsg.ambient(); math::Color ambient(msg.r(), msg.g(), msg.b(), msg.a()); material->SetAmbient(ambient); } @@ -1588,7 +1588,7 @@ MaterialPtr SubSceneManager::CreateMaterial( // set diffuse if available if (_materialMsg.has_diffuse()) { - sim::msgs::Color msg = _materialMsg.diffuse(); + gazebo::msgs::Color msg = _materialMsg.diffuse(); math::Color diffuse(msg.r(), msg.g(), msg.b(), msg.a()); material->SetDiffuse(diffuse); } @@ -1596,7 +1596,7 @@ MaterialPtr SubSceneManager::CreateMaterial( // set specular if available if (_materialMsg.has_specular()) { - sim::msgs::Color msg = _materialMsg.specular(); + gazebo::msgs::Color msg = _materialMsg.specular(); math::Color specular(msg.r(), msg.g(), msg.b(), msg.a()); material->SetSpecular(specular); } @@ -1604,7 +1604,7 @@ MaterialPtr SubSceneManager::CreateMaterial( // set emissive if available if (_materialMsg.has_emissive()) { - sim::msgs::Color msg = _materialMsg.emissive(); + gazebo::msgs::Color msg = _materialMsg.emissive(); math::Color emissive(msg.r(), msg.g(), msg.b(), msg.a()); material->SetEmissive(emissive); } @@ -1626,7 +1626,7 @@ MaterialPtr SubSceneManager::CreateMaterial( // set shader-type if available if (_materialMsg.has_shader_type()) { - sim::msgs::Material::ShaderType shader_type = + gazebo::msgs::Material::ShaderType shader_type = _materialMsg.shader_type(); ShaderType type = SubSceneManager::Convert(shader_type); material->SetShaderType(type); @@ -1638,7 +1638,7 @@ MaterialPtr SubSceneManager::CreateMaterial( } ////////////////////////////////////////////////// -void SubSceneManager::ProcessPose(const sim::msgs::Pose &_poseMsg) +void SubSceneManager::ProcessPose(const gazebo::msgs::Pose &_poseMsg) { std::string name = _poseMsg.name(); NodePtr node = this->activeScene->NodeByName(name); @@ -1647,7 +1647,7 @@ void SubSceneManager::ProcessPose(const sim::msgs::Pose &_poseMsg) ////////////////////////////////////////////////// void SubSceneManager::SetPose(NodePtr _node, - const sim::msgs::Pose &_poseMsg) + const gazebo::msgs::Pose &_poseMsg) { math::Pose3d pose = SubSceneManager::Convert(_poseMsg); _node->SetLocalPose(pose); @@ -1655,7 +1655,7 @@ void SubSceneManager::SetPose(NodePtr _node, ////////////////////////////////////////////////// void SubSceneManager::SetScale(VisualPtr _visual, - const sim::msgs::Vector3d &_scaleMsg) + const gazebo::msgs::Vector3d &_scaleMsg) { math::Vector3d scale = SubSceneManager::Convert(_scaleMsg); _visual->SetLocalScale(scale); @@ -1696,7 +1696,7 @@ void SubSceneManager::ProcessRemoval(const std::string &_name) } ////////////////////////////////////////////////// -math::Color SubSceneManager::Convert(const sim::msgs::Color &_colorMsg) +math::Color SubSceneManager::Convert(const gazebo::msgs::Color &_colorMsg) { math::Color color; color.R() = _colorMsg.r(); @@ -1707,21 +1707,21 @@ math::Color SubSceneManager::Convert(const sim::msgs::Color &_colorMsg) } ////////////////////////////////////////////////// -math::Pose3d SubSceneManager::Convert(const sim::msgs::Pose &_poseMsg) +math::Pose3d SubSceneManager::Convert(const gazebo::msgs::Pose &_poseMsg) { math::Pose3d pose; - const sim::msgs::Vector3d &posMsg = _poseMsg.position(); + const gazebo::msgs::Vector3d &posMsg = _poseMsg.position(); pose.Pos() = SubSceneManager::Convert(posMsg); - const sim::msgs::Quaternion &rotMsg = _poseMsg.orientation(); + const gazebo::msgs::Quaternion &rotMsg = _poseMsg.orientation(); pose.Rot() = SubSceneManager::Convert(rotMsg); return pose; } ////////////////////////////////////////////////// -math::Vector3d SubSceneManager::Convert(const sim::msgs::Vector3d &_vecMsg) +math::Vector3d SubSceneManager::Convert(const gazebo::msgs::Vector3d &_vecMsg) { math::Vector3d vec; vec.X(_vecMsg.x()); @@ -1732,7 +1732,7 @@ math::Vector3d SubSceneManager::Convert(const sim::msgs::Vector3d &_vecMsg) ////////////////////////////////////////////////// math::Quaterniond SubSceneManager::Convert( - const sim::msgs::Quaternion &_quatMsg) + const gazebo::msgs::Quaternion &_quatMsg) { math::Quaterniond quat; quat.W(_quatMsg.w()); @@ -1743,20 +1743,20 @@ math::Quaterniond SubSceneManager::Convert( } ////////////////////////////////////////////////// -ShaderType SubSceneManager::Convert(sim::msgs::Material::ShaderType _type) +ShaderType SubSceneManager::Convert(gazebo::msgs::Material::ShaderType _type) { switch (_type) { - case sim::msgs::Material::VERTEX: + case gazebo::msgs::Material::VERTEX: return ST_VERTEX; - case sim::msgs::Material::PIXEL: + case gazebo::msgs::Material::PIXEL: return ST_PIXEL; - case sim::msgs::Material::NORMAL_MAP_OBJECT_SPACE: + case gazebo::msgs::Material::NORMAL_MAP_OBJECT_SPACE: return ST_NORM_OBJ; - case sim::msgs::Material::NORMAL_MAP_TANGENT_SPACE: + case gazebo::msgs::Material::NORMAL_MAP_TANGENT_SPACE: return ST_NORM_TAN; default: @@ -1767,26 +1767,26 @@ ShaderType SubSceneManager::Convert(sim::msgs::Material::ShaderType _type) ////////////////////////////////////////////////// void SubSceneManager::CreateGeometryFunctionMap() { - this->geomFunctions[sim::msgs::Geometry::BOX] = + this->geomFunctions[gazebo::msgs::Geometry::BOX] = &SubSceneManager::ProcessBox; // TODO(anyone): enable when cone protobuf msg created - // this->geomFunctions[sim::msgs::Geometry::CONE] = + // this->geomFunctions[gazebo::msgs::Geometry::CONE] = // &SubSceneManager::ProcessCone; - this->geomFunctions[sim::msgs::Geometry::CYLINDER] = + this->geomFunctions[gazebo::msgs::Geometry::CYLINDER] = &SubSceneManager::ProcessCylinder; - this->geomFunctions[sim::msgs::Geometry::EMPTY] = + this->geomFunctions[gazebo::msgs::Geometry::EMPTY] = &SubSceneManager::ProcessEmpty; - this->geomFunctions[sim::msgs::Geometry::MESH] = + this->geomFunctions[gazebo::msgs::Geometry::MESH] = &SubSceneManager::ProcessMesh; - this->geomFunctions[sim::msgs::Geometry::PLANE] = + this->geomFunctions[gazebo::msgs::Geometry::PLANE] = &SubSceneManager::ProcessPlane; - this->geomFunctions[sim::msgs::Geometry::SPHERE] = + this->geomFunctions[gazebo::msgs::Geometry::SPHERE] = &SubSceneManager::ProcessSphere; } @@ -1812,7 +1812,7 @@ void CurrentSceneManager::OnPoseUpdate(::ConstPosesStampedPtr &_posesMsg) for (int i = 0; i < _posesMsg->pose_size(); ++i) { // replace into pose map - sim::msgs::Pose pose = _posesMsg->pose(i); + gazebo::msgs::Pose pose = _posesMsg->pose(i); std::string name = pose.name(); this->poseMsgs[name] = pose; } @@ -1945,7 +1945,7 @@ void NewSceneManager::ProcessScene() // process ambient if available if (this->sceneMsg.has_ambient()) { - sim::msgs::Color colorMsg = this->sceneMsg.ambient(); + gazebo::msgs::Color colorMsg = this->sceneMsg.ambient(); math::Color color(colorMsg.r(), colorMsg.g(), colorMsg.b()); this->activeScene->SetAmbientLight(color); } @@ -1953,7 +1953,7 @@ void NewSceneManager::ProcessScene() // process background if available if (this->sceneMsg.has_background()) { - sim::msgs::Color colorMsg = this->sceneMsg.background(); + gazebo::msgs::Color colorMsg = this->sceneMsg.background(); math::Color color(colorMsg.r(), colorMsg.g(), colorMsg.b()); this->activeScene->SetBackgroundColor(color); } @@ -1961,14 +1961,14 @@ void NewSceneManager::ProcessScene() // process each scene light for (int i = 0; i < this->sceneMsg.light_size(); ++i) { - sim::msgs::Light lightMsg = this->sceneMsg.light(i); + gazebo::msgs::Light lightMsg = this->sceneMsg.light(i); this->ProcessLight(lightMsg, this->activeScene->RootVisual()); } // process each scene model for (int i = 0; i < this->sceneMsg.model_size(); ++i) { - sim::msgs::Model modelMsg = this->sceneMsg.model(i); + gazebo::msgs::Model modelMsg = this->sceneMsg.model(i); this->ProcessModel(modelMsg, this->activeScene->RootVisual()); } } @@ -2040,7 +2040,7 @@ void NewSceneManager::ProcessPoses() } ////////////////////////////////////////////////// -void NewSceneManager::ProcessPoses(const sim::msgs::PosesStamped &_posesMsg) +void NewSceneManager::ProcessPoses(const gazebo::msgs::PosesStamped &_posesMsg) { // record pose timestamp int sec = _posesMsg.time().sec(); @@ -2050,7 +2050,7 @@ void NewSceneManager::ProcessPoses(const sim::msgs::PosesStamped &_posesMsg) // process each pose in list for (int i = 0; i < _posesMsg.pose_size(); ++i) { - sim::msgs::Pose poseMsg = _posesMsg.pose(i); + gazebo::msgs::Pose poseMsg = _posesMsg.pose(i); this->ProcessPose(poseMsg); } } diff --git a/examples/gazebo_scene_viewer/SceneManager.hh b/examples/gazebo_scene_viewer/SceneManager.hh index 62ef3758d..66ded0344 100644 --- a/examples/gazebo_scene_viewer/SceneManager.hh +++ b/examples/gazebo_scene_viewer/SceneManager.hh @@ -30,7 +30,7 @@ #include #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/examples/gazebo_scene_viewer/SceneManagerPrivate.hh b/examples/gazebo_scene_viewer/SceneManagerPrivate.hh index 29a7600f7..2d812e292 100644 --- a/examples/gazebo_scene_viewer/SceneManagerPrivate.hh +++ b/examples/gazebo_scene_viewer/SceneManagerPrivate.hh @@ -30,7 +30,7 @@ #include "gz/rendering/ShaderType.hh" #include "gazebo/transport/Node.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/ArrowVisual.hh b/include/gz/rendering/ArrowVisual.hh index cff3743b8..303b4121d 100644 --- a/include/gz/rendering/ArrowVisual.hh +++ b/include/gz/rendering/ArrowVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/CompositeVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/AxisVisual.hh b/include/gz/rendering/AxisVisual.hh index 873fc5ef9..e2147ee22 100644 --- a/include/gz/rendering/AxisVisual.hh +++ b/include/gz/rendering/AxisVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/CompositeVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Camera.hh b/include/gz/rendering/Camera.hh index 3859e84db..66d4074b8 100644 --- a/include/gz/rendering/Camera.hh +++ b/include/gz/rendering/Camera.hh @@ -29,7 +29,7 @@ #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/CompositeVisual.hh b/include/gz/rendering/CompositeVisual.hh index af4e4627e..05c307337 100644 --- a/include/gz/rendering/CompositeVisual.hh +++ b/include/gz/rendering/CompositeVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/DepthCamera.hh b/include/gz/rendering/DepthCamera.hh index 9c447362f..f86c935c6 100644 --- a/include/gz/rendering/DepthCamera.hh +++ b/include/gz/rendering/DepthCamera.hh @@ -22,7 +22,7 @@ #include #include "gz/rendering/Camera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/GaussianNoisePass.hh b/include/gz/rendering/GaussianNoisePass.hh index 97e91246f..4abaf9b7a 100644 --- a/include/gz/rendering/GaussianNoisePass.hh +++ b/include/gz/rendering/GaussianNoisePass.hh @@ -22,7 +22,7 @@ #include "gz/rendering/Export.hh" #include "gz/rendering/RenderPass.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Geometry.hh b/include/gz/rendering/Geometry.hh index 97a010a2c..6702576bb 100644 --- a/include/gz/rendering/Geometry.hh +++ b/include/gz/rendering/Geometry.hh @@ -23,7 +23,7 @@ #include "gz/rendering/Object.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/GizmoVisual.hh b/include/gz/rendering/GizmoVisual.hh index 63361a0e0..bc7bba0c6 100644 --- a/include/gz/rendering/GizmoVisual.hh +++ b/include/gz/rendering/GizmoVisual.hh @@ -23,7 +23,7 @@ #include "gz/rendering/Export.hh" #include "gz/rendering/TransformType.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/GpuRays.hh b/include/gz/rendering/GpuRays.hh index 9552064f7..080a73220 100644 --- a/include/gz/rendering/GpuRays.hh +++ b/include/gz/rendering/GpuRays.hh @@ -26,7 +26,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/Camera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Grid.hh b/include/gz/rendering/Grid.hh index e1d57b205..70fa66019 100644 --- a/include/gz/rendering/Grid.hh +++ b/include/gz/rendering/Grid.hh @@ -22,7 +22,7 @@ #include "gz/rendering/Geometry.hh" #include "gz/rendering/Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Image.hh b/include/gz/rendering/Image.hh index ba7155e7f..249c34b0c 100644 --- a/include/gz/rendering/Image.hh +++ b/include/gz/rendering/Image.hh @@ -25,7 +25,7 @@ #include "gz/rendering/PixelFormat.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Light.hh b/include/gz/rendering/Light.hh index cc10a8180..a908a98a5 100644 --- a/include/gz/rendering/Light.hh +++ b/include/gz/rendering/Light.hh @@ -21,7 +21,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Node.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Marker.hh b/include/gz/rendering/Marker.hh index cf08efdc6..f5e166821 100644 --- a/include/gz/rendering/Marker.hh +++ b/include/gz/rendering/Marker.hh @@ -25,7 +25,7 @@ #include "gz/rendering/Object.hh" #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Material.hh b/include/gz/rendering/Material.hh index c26d8b7d3..086185f4f 100644 --- a/include/gz/rendering/Material.hh +++ b/include/gz/rendering/Material.hh @@ -26,7 +26,7 @@ #include "gz/rendering/ShaderType.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Mesh.hh b/include/gz/rendering/Mesh.hh index 6f22d785f..4abafd126 100644 --- a/include/gz/rendering/Mesh.hh +++ b/include/gz/rendering/Mesh.hh @@ -24,7 +24,7 @@ #include "gz/rendering/Geometry.hh" #include "gz/rendering/Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/MeshDescriptor.hh b/include/gz/rendering/MeshDescriptor.hh index a3455a91e..2dc15b0dd 100644 --- a/include/gz/rendering/MeshDescriptor.hh +++ b/include/gz/rendering/MeshDescriptor.hh @@ -24,7 +24,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace common { @@ -32,7 +32,7 @@ namespace gz } } -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/MoveToHelper.hh b/include/gz/rendering/MoveToHelper.hh index 3b6d015b4..d6ca753eb 100644 --- a/include/gz/rendering/MoveToHelper.hh +++ b/include/gz/rendering/MoveToHelper.hh @@ -27,7 +27,7 @@ #include "gz/rendering/Camera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Node.hh b/include/gz/rendering/Node.hh index 01b8189e7..3e1fce508 100644 --- a/include/gz/rendering/Node.hh +++ b/include/gz/rendering/Node.hh @@ -26,7 +26,7 @@ #include "gz/rendering/Object.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Object.hh b/include/gz/rendering/Object.hh index ef9c31063..1d33a29b5 100644 --- a/include/gz/rendering/Object.hh +++ b/include/gz/rendering/Object.hh @@ -22,7 +22,7 @@ #include "gz/rendering/RenderTypes.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/OrbitViewController.hh b/include/gz/rendering/OrbitViewController.hh index 2b2a9497a..d10b8fd48 100644 --- a/include/gz/rendering/OrbitViewController.hh +++ b/include/gz/rendering/OrbitViewController.hh @@ -27,7 +27,7 @@ #include "gz/rendering/Camera.hh" #include "gz/rendering/ViewController.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/PixelFormat.hh b/include/gz/rendering/PixelFormat.hh index 465070776..6542a321d 100644 --- a/include/gz/rendering/PixelFormat.hh +++ b/include/gz/rendering/PixelFormat.hh @@ -21,7 +21,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RayQuery.hh b/include/gz/rendering/RayQuery.hh index 91050f081..4beca9b6c 100644 --- a/include/gz/rendering/RayQuery.hh +++ b/include/gz/rendering/RayQuery.hh @@ -25,7 +25,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderEngine.hh b/include/gz/rendering/RenderEngine.hh index fa3249387..6255a218f 100644 --- a/include/gz/rendering/RenderEngine.hh +++ b/include/gz/rendering/RenderEngine.hh @@ -23,7 +23,7 @@ #include "gz/rendering/RenderTypes.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderEngineManager.hh b/include/gz/rendering/RenderEngineManager.hh index 5c1eac4e3..d7391338b 100644 --- a/include/gz/rendering/RenderEngineManager.hh +++ b/include/gz/rendering/RenderEngineManager.hh @@ -27,7 +27,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderEnginePlugin.hh b/include/gz/rendering/RenderEnginePlugin.hh index 5aff6a044..7afe29ed4 100644 --- a/include/gz/rendering/RenderEnginePlugin.hh +++ b/include/gz/rendering/RenderEnginePlugin.hh @@ -26,7 +26,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderPass.hh b/include/gz/rendering/RenderPass.hh index 7d9b907bd..e012285b0 100644 --- a/include/gz/rendering/RenderPass.hh +++ b/include/gz/rendering/RenderPass.hh @@ -21,7 +21,7 @@ #include "gz/rendering/Object.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderPassSystem.hh b/include/gz/rendering/RenderPassSystem.hh index 6b34c8962..271d76f2e 100644 --- a/include/gz/rendering/RenderPassSystem.hh +++ b/include/gz/rendering/RenderPassSystem.hh @@ -29,7 +29,7 @@ #include "gz/rendering/RenderPass.hh" #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderTarget.hh b/include/gz/rendering/RenderTarget.hh index d8e0f7233..1a30a7786 100644 --- a/include/gz/rendering/RenderTarget.hh +++ b/include/gz/rendering/RenderTarget.hh @@ -26,7 +26,7 @@ #include "gz/rendering/Image.hh" #include "gz/rendering/Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderTypes.hh b/include/gz/rendering/RenderTypes.hh index f74131613..dab356b62 100644 --- a/include/gz/rendering/RenderTypes.hh +++ b/include/gz/rendering/RenderTypes.hh @@ -37,7 +37,7 @@ /// \brief Render visuals that are selectable mask. #define IGN_VISIBILITY_SELECTABLE 0x00000002 -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/RenderingIface.hh b/include/gz/rendering/RenderingIface.hh index 0bfe0194b..13825ee77 100644 --- a/include/gz/rendering/RenderingIface.hh +++ b/include/gz/rendering/RenderingIface.hh @@ -26,7 +26,7 @@ #include "gz/rendering/Export.hh" #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Scene.hh b/include/gz/rendering/Scene.hh index 68de5832f..11759e2f4 100644 --- a/include/gz/rendering/Scene.hh +++ b/include/gz/rendering/Scene.hh @@ -33,7 +33,7 @@ #include "gz/rendering/Storage.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Sensor.hh b/include/gz/rendering/Sensor.hh index db5be49fc..e997e02c5 100644 --- a/include/gz/rendering/Sensor.hh +++ b/include/gz/rendering/Sensor.hh @@ -20,7 +20,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Node.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/ShaderParam.hh b/include/gz/rendering/ShaderParam.hh index 94a52c504..a146bb0b4 100644 --- a/include/gz/rendering/ShaderParam.hh +++ b/include/gz/rendering/ShaderParam.hh @@ -26,7 +26,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/ShaderParams.hh b/include/gz/rendering/ShaderParams.hh index a188a591c..b575d081f 100644 --- a/include/gz/rendering/ShaderParams.hh +++ b/include/gz/rendering/ShaderParams.hh @@ -25,7 +25,7 @@ #include "gz/rendering/Export.hh" #include "gz/rendering/ShaderParam.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/ShaderType.hh b/include/gz/rendering/ShaderType.hh index e5b66c861..f4d87ccc4 100644 --- a/include/gz/rendering/ShaderType.hh +++ b/include/gz/rendering/ShaderType.hh @@ -21,7 +21,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Storage.hh b/include/gz/rendering/Storage.hh index 0fa0102b5..8a94e1f3f 100644 --- a/include/gz/rendering/Storage.hh +++ b/include/gz/rendering/Storage.hh @@ -36,7 +36,7 @@ #undef DestroyAll #endif -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Text.hh b/include/gz/rendering/Text.hh index 2d19617b4..96e8bc228 100644 --- a/include/gz/rendering/Text.hh +++ b/include/gz/rendering/Text.hh @@ -26,7 +26,7 @@ #include "gz/rendering/Geometry.hh" #include "gz/rendering/Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/ThermalCamera.hh b/include/gz/rendering/ThermalCamera.hh index 1e399693c..077c9a3a9 100644 --- a/include/gz/rendering/ThermalCamera.hh +++ b/include/gz/rendering/ThermalCamera.hh @@ -20,7 +20,7 @@ #include #include "gz/rendering/Camera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/TransformController.hh b/include/gz/rendering/TransformController.hh index 8b039c19d..9e35d6cef 100644 --- a/include/gz/rendering/TransformController.hh +++ b/include/gz/rendering/TransformController.hh @@ -30,7 +30,7 @@ #include "gz/rendering/GizmoVisual.hh" #include "gz/rendering/TransformType.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/TransformType.hh b/include/gz/rendering/TransformType.hh index 5e6cf99ea..158b4d07b 100644 --- a/include/gz/rendering/TransformType.hh +++ b/include/gz/rendering/TransformType.hh @@ -23,7 +23,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Utils.hh b/include/gz/rendering/Utils.hh index 83dbc8e18..b2819201e 100644 --- a/include/gz/rendering/Utils.hh +++ b/include/gz/rendering/Utils.hh @@ -27,7 +27,7 @@ #include "gz/rendering/RayQuery.hh" -namespace gz +namespace ignition { /// \brief Rendering classes and function useful in robot applications. namespace rendering diff --git a/include/gz/rendering/ViewController.hh b/include/gz/rendering/ViewController.hh index 462640e07..dbde046e0 100644 --- a/include/gz/rendering/ViewController.hh +++ b/include/gz/rendering/ViewController.hh @@ -23,7 +23,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Camera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/Visual.hh b/include/gz/rendering/Visual.hh index 331d189be..d085b66a4 100644 --- a/include/gz/rendering/Visual.hh +++ b/include/gz/rendering/Visual.hh @@ -22,7 +22,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/Node.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseArrowVisual.hh b/include/gz/rendering/base/BaseArrowVisual.hh index b3804e732..807699fde 100644 --- a/include/gz/rendering/base/BaseArrowVisual.hh +++ b/include/gz/rendering/base/BaseArrowVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/ArrowVisual.hh" #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseAxisVisual.hh b/include/gz/rendering/base/BaseAxisVisual.hh index 60500a235..b7cffb664 100644 --- a/include/gz/rendering/base/BaseAxisVisual.hh +++ b/include/gz/rendering/base/BaseAxisVisual.hh @@ -21,7 +21,7 @@ #include "gz/rendering/ArrowVisual.hh" #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseCamera.hh b/include/gz/rendering/base/BaseCamera.hh index 36bb10bc5..2d02fa9f2 100644 --- a/include/gz/rendering/base/BaseCamera.hh +++ b/include/gz/rendering/base/BaseCamera.hh @@ -32,7 +32,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/base/BaseRenderTarget.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseDepthCamera.hh b/include/gz/rendering/base/BaseDepthCamera.hh index 9db70453b..9781fae90 100644 --- a/include/gz/rendering/base/BaseDepthCamera.hh +++ b/include/gz/rendering/base/BaseDepthCamera.hh @@ -24,7 +24,7 @@ #include "gz/rendering/base/BaseCamera.hh" #include "gz/rendering/DepthCamera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseGaussianNoisePass.hh b/include/gz/rendering/base/BaseGaussianNoisePass.hh index 8642db159..82a99c014 100644 --- a/include/gz/rendering/base/BaseGaussianNoisePass.hh +++ b/include/gz/rendering/base/BaseGaussianNoisePass.hh @@ -22,7 +22,7 @@ #include "gz/rendering/GaussianNoisePass.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseGeometry.hh b/include/gz/rendering/base/BaseGeometry.hh index 2594a18ba..e21e3ce3b 100644 --- a/include/gz/rendering/base/BaseGeometry.hh +++ b/include/gz/rendering/base/BaseGeometry.hh @@ -21,7 +21,7 @@ #include "gz/rendering/Geometry.hh" #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseGizmoVisual.hh b/include/gz/rendering/base/BaseGizmoVisual.hh index 7e789925b..ccc329941 100644 --- a/include/gz/rendering/base/BaseGizmoVisual.hh +++ b/include/gz/rendering/base/BaseGizmoVisual.hh @@ -29,7 +29,7 @@ #include "gz/rendering/Camera.hh" #include "gz/rendering/GizmoVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseGpuRays.hh b/include/gz/rendering/base/BaseGpuRays.hh index 333f9ab8c..54f84e8d5 100644 --- a/include/gz/rendering/base/BaseGpuRays.hh +++ b/include/gz/rendering/base/BaseGpuRays.hh @@ -32,7 +32,7 @@ #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseGrid.hh b/include/gz/rendering/base/BaseGrid.hh index c1370e21b..899f703ff 100644 --- a/include/gz/rendering/base/BaseGrid.hh +++ b/include/gz/rendering/base/BaseGrid.hh @@ -21,7 +21,7 @@ #include "gz/rendering/Grid.hh" #include "gz/rendering/base/BaseObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseLight.hh b/include/gz/rendering/base/BaseLight.hh index 572f31555..6993fb235 100644 --- a/include/gz/rendering/base/BaseLight.hh +++ b/include/gz/rendering/base/BaseLight.hh @@ -19,7 +19,7 @@ #include "gz/rendering/Light.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseMarker.hh b/include/gz/rendering/base/BaseMarker.hh index 6ec32943d..3ecd3ab54 100644 --- a/include/gz/rendering/base/BaseMarker.hh +++ b/include/gz/rendering/base/BaseMarker.hh @@ -23,7 +23,7 @@ #include "gz/rendering/base/BaseObject.hh" #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseMaterial.hh b/include/gz/rendering/base/BaseMaterial.hh index 6a654ad8b..a7213c21b 100644 --- a/include/gz/rendering/base/BaseMaterial.hh +++ b/include/gz/rendering/base/BaseMaterial.hh @@ -25,7 +25,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/ShaderType.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseMesh.hh b/include/gz/rendering/base/BaseMesh.hh index 2e3f371cc..7ae3304a4 100644 --- a/include/gz/rendering/base/BaseMesh.hh +++ b/include/gz/rendering/base/BaseMesh.hh @@ -23,7 +23,7 @@ #include "gz/rendering/Storage.hh" #include "gz/rendering/base/BaseObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseNode.hh b/include/gz/rendering/base/BaseNode.hh index 0739f7954..8309d7b3d 100644 --- a/include/gz/rendering/base/BaseNode.hh +++ b/include/gz/rendering/base/BaseNode.hh @@ -22,7 +22,7 @@ #include "gz/rendering/Storage.hh" #include "gz/rendering/base/BaseStorage.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseObject.hh b/include/gz/rendering/base/BaseObject.hh index 4e57496c7..65f61c9d5 100644 --- a/include/gz/rendering/base/BaseObject.hh +++ b/include/gz/rendering/base/BaseObject.hh @@ -22,7 +22,7 @@ #include #include "gz/rendering/Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseRayQuery.hh b/include/gz/rendering/base/BaseRayQuery.hh index 8f36b0eb4..7648b8d48 100644 --- a/include/gz/rendering/base/BaseRayQuery.hh +++ b/include/gz/rendering/base/BaseRayQuery.hh @@ -23,7 +23,7 @@ #include "gz/rendering/RayQuery.hh" #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseRenderEngine.hh b/include/gz/rendering/base/BaseRenderEngine.hh index 5b8292f04..e3aa072c0 100644 --- a/include/gz/rendering/base/BaseRenderEngine.hh +++ b/include/gz/rendering/base/BaseRenderEngine.hh @@ -24,7 +24,7 @@ #include "gz/rendering/RenderEngine.hh" #include "gz/rendering/Storage.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseRenderPass.hh b/include/gz/rendering/base/BaseRenderPass.hh index 9e2d54c93..d380f67e1 100644 --- a/include/gz/rendering/base/BaseRenderPass.hh +++ b/include/gz/rendering/base/BaseRenderPass.hh @@ -20,7 +20,7 @@ #include #include "gz/rendering/RenderPass.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseRenderTarget.hh b/include/gz/rendering/base/BaseRenderTarget.hh index d73d22d6c..adaf34869 100644 --- a/include/gz/rendering/base/BaseRenderTarget.hh +++ b/include/gz/rendering/base/BaseRenderTarget.hh @@ -25,7 +25,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseRenderTypes.hh b/include/gz/rendering/base/BaseRenderTypes.hh index f5343e1dc..bda3c2506 100644 --- a/include/gz/rendering/base/BaseRenderTypes.hh +++ b/include/gz/rendering/base/BaseRenderTypes.hh @@ -21,7 +21,7 @@ #include "gz/rendering/RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseScene.hh b/include/gz/rendering/base/BaseScene.hh index 1f4cbef63..8e8e805ed 100644 --- a/include/gz/rendering/base/BaseScene.hh +++ b/include/gz/rendering/base/BaseScene.hh @@ -28,7 +28,7 @@ #include "gz/rendering/Scene.hh" #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseSensor.hh b/include/gz/rendering/base/BaseSensor.hh index a0f30a167..6c52be724 100644 --- a/include/gz/rendering/base/BaseSensor.hh +++ b/include/gz/rendering/base/BaseSensor.hh @@ -19,7 +19,7 @@ #include "gz/rendering/Sensor.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseStorage.hh b/include/gz/rendering/base/BaseStorage.hh index b4906d8c8..89b8785b6 100644 --- a/include/gz/rendering/base/BaseStorage.hh +++ b/include/gz/rendering/base/BaseStorage.hh @@ -27,7 +27,7 @@ #include "gz/rendering/Storage.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseText.hh b/include/gz/rendering/base/BaseText.hh index 3a15de8b9..0f5774da2 100644 --- a/include/gz/rendering/base/BaseText.hh +++ b/include/gz/rendering/base/BaseText.hh @@ -21,7 +21,7 @@ #include "gz/rendering/Text.hh" #include "gz/rendering/base/BaseObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseThermalCamera.hh b/include/gz/rendering/base/BaseThermalCamera.hh index 40c138cbd..a0bee4984 100644 --- a/include/gz/rendering/base/BaseThermalCamera.hh +++ b/include/gz/rendering/base/BaseThermalCamera.hh @@ -22,7 +22,7 @@ #include "gz/rendering/base/BaseCamera.hh" #include "gz/rendering/ThermalCamera.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/base/BaseVisual.hh b/include/gz/rendering/base/BaseVisual.hh index 7288e5253..050006e36 100644 --- a/include/gz/rendering/base/BaseVisual.hh +++ b/include/gz/rendering/base/BaseVisual.hh @@ -25,7 +25,7 @@ #include "gz/rendering/RenderEngine.hh" #include "gz/rendering/base/BaseStorage.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/include/gz/rendering/config.hh.in b/include/gz/rendering/config.hh.in index fd052ebf6..0a74f1205 100644 --- a/include/gz/rendering/config.hh.in +++ b/include/gz/rendering/config.hh.in @@ -24,3 +24,12 @@ #cmakedefine HAVE_OPTIX 1 #cmakedefine HAVE_GAZEBO 1 #cmakedefine INCLUDE_RTSHADER 1 + +namespace ignition +{ +} + +namespace gz +{ + using namespace ignition; +} diff --git a/include/ignition/rendering/config.hh b/include/ignition/rendering/config.hh index 73cd9b22e..6dd936c31 100644 --- a/include/ignition/rendering/config.hh +++ b/include/ignition/rendering/config.hh @@ -45,14 +45,4 @@ /* #undef HAVE_GAZEBO */ /* #undef INCLUDE_RTSHADER */ -namespace gz -{ -} - -namespace ignition -{ - using namespace gz; -} - - #endif diff --git a/ogre/include/gz/rendering/ogre/OgreArrowVisual.hh b/ogre/include/gz/rendering/ogre/OgreArrowVisual.hh index 3a9f9b565..9bdb05a61 100644 --- a/ogre/include/gz/rendering/ogre/OgreArrowVisual.hh +++ b/ogre/include/gz/rendering/ogre/OgreArrowVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseArrowVisual.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreAxisVisual.hh b/ogre/include/gz/rendering/ogre/OgreAxisVisual.hh index 7ee7979cd..aa4277a98 100644 --- a/ogre/include/gz/rendering/ogre/OgreAxisVisual.hh +++ b/ogre/include/gz/rendering/ogre/OgreAxisVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseAxisVisual.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreCamera.hh b/ogre/include/gz/rendering/ogre/OgreCamera.hh index a35630e43..feced1ee3 100644 --- a/ogre/include/gz/rendering/ogre/OgreCamera.hh +++ b/ogre/include/gz/rendering/ogre/OgreCamera.hh @@ -29,7 +29,7 @@ namespace Ogre class Camera; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreConversions.hh b/ogre/include/gz/rendering/ogre/OgreConversions.hh index 522f650b3..1783addda 100644 --- a/ogre/include/gz/rendering/ogre/OgreConversions.hh +++ b/ogre/include/gz/rendering/ogre/OgreConversions.hh @@ -26,7 +26,7 @@ #include "gz/rendering/ogre/OgreIncludes.hh" #include "gz/rendering/ogre/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreDepthCamera.hh b/ogre/include/gz/rendering/ogre/OgreDepthCamera.hh index e7fd26e9c..7fa9c1950 100644 --- a/ogre/include/gz/rendering/ogre/OgreDepthCamera.hh +++ b/ogre/include/gz/rendering/ogre/OgreDepthCamera.hh @@ -49,7 +49,7 @@ namespace Ogre class Viewport; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreDynamicLines.hh b/ogre/include/gz/rendering/ogre/OgreDynamicLines.hh index 6ccc70433..490f02963 100644 --- a/ogre/include/gz/rendering/ogre/OgreDynamicLines.hh +++ b/ogre/include/gz/rendering/ogre/OgreDynamicLines.hh @@ -26,7 +26,7 @@ #include "gz/rendering/ogre/OgreConversions.hh" #include "gz/rendering/ogre/OgreDynamicRenderable.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreDynamicRenderable.hh b/ogre/include/gz/rendering/ogre/OgreDynamicRenderable.hh index 878c2c31c..73a28cfa9 100644 --- a/ogre/include/gz/rendering/ogre/OgreDynamicRenderable.hh +++ b/ogre/include/gz/rendering/ogre/OgreDynamicRenderable.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre/OgreRenderTypes.hh" #include "gz/rendering/Marker.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreGaussianNoisePass.hh b/ogre/include/gz/rendering/ogre/OgreGaussianNoisePass.hh index 857e8d268..453ee2a50 100644 --- a/ogre/include/gz/rendering/ogre/OgreGaussianNoisePass.hh +++ b/ogre/include/gz/rendering/ogre/OgreGaussianNoisePass.hh @@ -26,7 +26,7 @@ #include "gz/rendering/ogre/OgreRenderPass.hh" #include "gz/rendering/ogre/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreGeometry.hh b/ogre/include/gz/rendering/ogre/OgreGeometry.hh index 4f8f4a796..55e3ad4bd 100644 --- a/ogre/include/gz/rendering/ogre/OgreGeometry.hh +++ b/ogre/include/gz/rendering/ogre/OgreGeometry.hh @@ -27,7 +27,7 @@ namespace Ogre class MovableObject; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreGizmoVisual.hh b/ogre/include/gz/rendering/ogre/OgreGizmoVisual.hh index 177ba587d..c871c3703 100644 --- a/ogre/include/gz/rendering/ogre/OgreGizmoVisual.hh +++ b/ogre/include/gz/rendering/ogre/OgreGizmoVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseGizmoVisual.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreGpuRays.hh b/ogre/include/gz/rendering/ogre/OgreGpuRays.hh index dd99fee34..ce1a12ffd 100644 --- a/ogre/include/gz/rendering/ogre/OgreGpuRays.hh +++ b/ogre/include/gz/rendering/ogre/OgreGpuRays.hh @@ -41,7 +41,7 @@ #include #endif -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreGrid.hh b/ogre/include/gz/rendering/ogre/OgreGrid.hh index 9faa27ae9..6a577051b 100644 --- a/ogre/include/gz/rendering/ogre/OgreGrid.hh +++ b/ogre/include/gz/rendering/ogre/OgreGrid.hh @@ -28,7 +28,7 @@ namespace Ogre class MovableObject; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreLight.hh b/ogre/include/gz/rendering/ogre/OgreLight.hh index 431c804e2..a8c537d52 100644 --- a/ogre/include/gz/rendering/ogre/OgreLight.hh +++ b/ogre/include/gz/rendering/ogre/OgreLight.hh @@ -26,7 +26,7 @@ namespace Ogre class Light; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreMarker.hh b/ogre/include/gz/rendering/ogre/OgreMarker.hh index e787fe037..3c0a4bd51 100644 --- a/ogre/include/gz/rendering/ogre/OgreMarker.hh +++ b/ogre/include/gz/rendering/ogre/OgreMarker.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre/OgreGeometry.hh" #include "gz/rendering/ogre/OgreIncludes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreMaterial.hh b/ogre/include/gz/rendering/ogre/OgreMaterial.hh index 5a4524c39..f29cc596d 100644 --- a/ogre/include/gz/rendering/ogre/OgreMaterial.hh +++ b/ogre/include/gz/rendering/ogre/OgreMaterial.hh @@ -25,7 +25,7 @@ #include "gz/rendering/ogre/OgreObject.hh" #include "gz/rendering/ogre/OgreIncludes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreMaterialSwitcher.hh b/ogre/include/gz/rendering/ogre/OgreMaterialSwitcher.hh index 3f7636b39..141cfff4f 100644 --- a/ogre/include/gz/rendering/ogre/OgreMaterialSwitcher.hh +++ b/ogre/include/gz/rendering/ogre/OgreMaterialSwitcher.hh @@ -28,7 +28,7 @@ #include "gz/rendering/ogre/OgreIncludes.hh" #include "gz/rendering/ogre/OgreRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreMesh.hh b/ogre/include/gz/rendering/ogre/OgreMesh.hh index 76b327e9a..fb8165fdb 100644 --- a/ogre/include/gz/rendering/ogre/OgreMesh.hh +++ b/ogre/include/gz/rendering/ogre/OgreMesh.hh @@ -31,7 +31,7 @@ namespace Ogre class SubEntity; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreMeshFactory.hh b/ogre/include/gz/rendering/ogre/OgreMeshFactory.hh index fa7286ac3..9c6aaf8f7 100644 --- a/ogre/include/gz/rendering/ogre/OgreMeshFactory.hh +++ b/ogre/include/gz/rendering/ogre/OgreMeshFactory.hh @@ -29,7 +29,7 @@ namespace Ogre class Entity; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreNode.hh b/ogre/include/gz/rendering/ogre/OgreNode.hh index e2570b485..28c641680 100644 --- a/ogre/include/gz/rendering/ogre/OgreNode.hh +++ b/ogre/include/gz/rendering/ogre/OgreNode.hh @@ -28,7 +28,7 @@ namespace Ogre class SceneNode; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreObject.hh b/ogre/include/gz/rendering/ogre/OgreObject.hh index 95da99ed4..4acc1acc1 100644 --- a/ogre/include/gz/rendering/ogre/OgreObject.hh +++ b/ogre/include/gz/rendering/ogre/OgreObject.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre/OgreRenderTypes.hh" #include "gz/rendering/ogre/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRTShaderSystem.hh b/ogre/include/gz/rendering/ogre/OgreRTShaderSystem.hh index a2827e9c1..1e4d1611b 100644 --- a/ogre/include/gz/rendering/ogre/OgreRTShaderSystem.hh +++ b/ogre/include/gz/rendering/ogre/OgreRTShaderSystem.hh @@ -25,7 +25,7 @@ #include "gz/rendering/ogre/OgreRenderTypes.hh" #include "gz/rendering/ogre/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRayQuery.hh b/ogre/include/gz/rendering/ogre/OgreRayQuery.hh index feceab193..1e3c527b0 100644 --- a/ogre/include/gz/rendering/ogre/OgreRayQuery.hh +++ b/ogre/include/gz/rendering/ogre/OgreRayQuery.hh @@ -24,7 +24,7 @@ #include "gz/rendering/ogre/OgreObject.hh" #include "gz/rendering/ogre/OgreRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRenderEngine.hh b/ogre/include/gz/rendering/ogre/OgreRenderEngine.hh index 98aa1947b..dd168a5cf 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderEngine.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderEngine.hh @@ -37,7 +37,7 @@ namespace Ogre class Root; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRenderPass.hh b/ogre/include/gz/rendering/ogre/OgreRenderPass.hh index b66386898..629045cb4 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderPass.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderPass.hh @@ -22,7 +22,7 @@ #include "gz/rendering/ogre/OgreIncludes.hh" #include "gz/rendering/ogre/OgreObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRenderTarget.hh b/ogre/include/gz/rendering/ogre/OgreRenderTarget.hh index 9b9f15146..f66a37317 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderTarget.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderTarget.hh @@ -33,7 +33,7 @@ namespace Ogre class Texture; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRenderTargetMaterial.hh b/ogre/include/gz/rendering/ogre/OgreRenderTargetMaterial.hh index 900444908..627709d86 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderTargetMaterial.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderTargetMaterial.hh @@ -31,7 +31,7 @@ #pragma warning(disable:4275) #endif -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh b/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh index 533c504bd..da5a955b0 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh @@ -20,7 +20,7 @@ #include #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreScene.hh b/ogre/include/gz/rendering/ogre/OgreScene.hh index cdfe3b8f9..02b4f8dd8 100644 --- a/ogre/include/gz/rendering/ogre/OgreScene.hh +++ b/ogre/include/gz/rendering/ogre/OgreScene.hh @@ -30,7 +30,7 @@ namespace Ogre class SceneManager; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreSelectionBuffer.hh b/ogre/include/gz/rendering/ogre/OgreSelectionBuffer.hh index f88a68fec..3a6932018 100644 --- a/ogre/include/gz/rendering/ogre/OgreSelectionBuffer.hh +++ b/ogre/include/gz/rendering/ogre/OgreSelectionBuffer.hh @@ -30,7 +30,7 @@ namespace Ogre class SceneManager; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreSensor.hh b/ogre/include/gz/rendering/ogre/OgreSensor.hh index 20e509611..af5643099 100644 --- a/ogre/include/gz/rendering/ogre/OgreSensor.hh +++ b/ogre/include/gz/rendering/ogre/OgreSensor.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseSensor.hh" #include "gz/rendering/ogre/OgreNode.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreStorage.hh b/ogre/include/gz/rendering/ogre/OgreStorage.hh index 1e8df4884..50db5882b 100644 --- a/ogre/include/gz/rendering/ogre/OgreStorage.hh +++ b/ogre/include/gz/rendering/ogre/OgreStorage.hh @@ -29,7 +29,7 @@ #include "gz/rendering/ogre/OgreSensor.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreText.hh b/ogre/include/gz/rendering/ogre/OgreText.hh index 25f5bc0df..fdda47cf1 100644 --- a/ogre/include/gz/rendering/ogre/OgreText.hh +++ b/ogre/include/gz/rendering/ogre/OgreText.hh @@ -29,7 +29,7 @@ #include "gz/rendering/ogre/OgreIncludes.hh" #include "gz/rendering/ogre/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreThermalCamera.hh b/ogre/include/gz/rendering/ogre/OgreThermalCamera.hh index eed59aefd..28acb3dd2 100644 --- a/ogre/include/gz/rendering/ogre/OgreThermalCamera.hh +++ b/ogre/include/gz/rendering/ogre/OgreThermalCamera.hh @@ -47,7 +47,7 @@ namespace Ogre class Camera; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/include/gz/rendering/ogre/OgreVisual.hh b/ogre/include/gz/rendering/ogre/OgreVisual.hh index 93a11f2d8..f24fda216 100644 --- a/ogre/include/gz/rendering/ogre/OgreVisual.hh +++ b/ogre/include/gz/rendering/ogre/OgreVisual.hh @@ -21,7 +21,7 @@ #include "gz/rendering/ogre/OgreNode.hh" #include "gz/rendering/ogre/OgreRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/src/OgreGaussianNoisePass.cc b/ogre/src/OgreGaussianNoisePass.cc index e40375b74..0f81ab498 100644 --- a/ogre/src/OgreGaussianNoisePass.cc +++ b/ogre/src/OgreGaussianNoisePass.cc @@ -22,7 +22,7 @@ #include "gz/rendering/ogre/OgreIncludes.hh" #include "gz/rendering/ogre/OgreGaussianNoisePass.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/src/OgreScene.cc b/ogre/src/OgreScene.cc index 8b3c6c046..bf979443c 100644 --- a/ogre/src/OgreScene.cc +++ b/ogre/src/OgreScene.cc @@ -40,7 +40,7 @@ #include "gz/rendering/ogre/OgreThermalCamera.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre/src/OgreThermalCamera.cc b/ogre/src/OgreThermalCamera.cc index 1b9e1ecdf..68c468e9a 100644 --- a/ogre/src/OgreThermalCamera.cc +++ b/ogre/src/OgreThermalCamera.cc @@ -31,7 +31,7 @@ #include "gz/rendering/ogre/OgreMaterial.hh" #include "gz/rendering/ogre/OgreVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Camera.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Camera.hh index e9d9bc133..c2ec52d31 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Camera.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Camera.hh @@ -26,7 +26,7 @@ namespace Ogre class Camera; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Conversions.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Conversions.hh index d71a9dcc0..63ea87942 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Conversions.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Conversions.hh @@ -27,7 +27,7 @@ #include "gz/rendering/ogre2/Ogre2Includes.hh" #include "gz/rendering/ogre2/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2DepthCamera.hh b/ogre2/include/gz/rendering/ogre2/Ogre2DepthCamera.hh index 5481024fb..6e1aafcdd 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2DepthCamera.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2DepthCamera.hh @@ -42,7 +42,7 @@ namespace Ogre class Viewport; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2DynamicRenderable.hh b/ogre2/include/gz/rendering/ogre2/Ogre2DynamicRenderable.hh index 168c6c8a0..44deed64a 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2DynamicRenderable.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2DynamicRenderable.hh @@ -26,7 +26,7 @@ #include "gz/rendering/ogre2/Ogre2RenderTypes.hh" #include "gz/rendering/Marker.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2GaussianNoisePass.hh b/ogre2/include/gz/rendering/ogre2/Ogre2GaussianNoisePass.hh index 1fc33b6a4..41892184f 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2GaussianNoisePass.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2GaussianNoisePass.hh @@ -22,7 +22,7 @@ #include "gz/rendering/ogre2/Ogre2RenderPass.hh" #include "gz/rendering/ogre2/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Geometry.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Geometry.hh index be8730b54..04f2e2b9b 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Geometry.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Geometry.hh @@ -25,7 +25,7 @@ namespace Ogre class MovableObject; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2GizmoVisual.hh b/ogre2/include/gz/rendering/ogre2/Ogre2GizmoVisual.hh index 9681d2afc..149c06d90 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2GizmoVisual.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2GizmoVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseGizmoVisual.hh" #include "gz/rendering/ogre2/Ogre2Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2GpuRays.hh b/ogre2/include/gz/rendering/ogre2/Ogre2GpuRays.hh index 5bccb331b..c02725e56 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2GpuRays.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2GpuRays.hh @@ -41,7 +41,7 @@ namespace Ogre class Viewport; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Grid.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Grid.hh index 414856b51..4f9867178 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Grid.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Grid.hh @@ -28,7 +28,7 @@ namespace Ogre class MovableObject; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Light.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Light.hh index 183fad17a..12f27d80e 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Light.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Light.hh @@ -26,7 +26,7 @@ namespace Ogre class Light; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Marker.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Marker.hh index bab534fa7..0b320e836 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Marker.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Marker.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre2/Ogre2Geometry.hh" #include "gz/rendering/ogre2/Ogre2Includes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Material.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Material.hh index ce8eef513..6f9787170 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Material.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Material.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre2/Ogre2Object.hh" #include "gz/rendering/ogre2/Ogre2Includes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2MaterialSwitcher.hh b/ogre2/include/gz/rendering/ogre2/Ogre2MaterialSwitcher.hh index 0cf5137c3..a673161f9 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2MaterialSwitcher.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2MaterialSwitcher.hh @@ -27,7 +27,7 @@ #include "gz/rendering/ogre2/Ogre2Includes.hh" #include "gz/rendering/ogre2/Ogre2RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Mesh.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Mesh.hh index 42bb4d4b2..f9b76493a 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Mesh.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Mesh.hh @@ -31,7 +31,7 @@ namespace Ogre class SubItem; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2MeshFactory.hh b/ogre2/include/gz/rendering/ogre2/Ogre2MeshFactory.hh index 77a09bf3e..a6478000f 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2MeshFactory.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2MeshFactory.hh @@ -31,7 +31,7 @@ namespace Ogre class Item; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Node.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Node.hh index 5290e0bd4..bcf40ffb3 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Node.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Node.hh @@ -26,7 +26,7 @@ namespace Ogre class SceneNode; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Object.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Object.hh index 8d20a2b0e..50042bfc6 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Object.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Object.hh @@ -22,7 +22,7 @@ #include "gz/rendering/ogre2/Ogre2RenderTypes.hh" #include "gz/rendering/ogre2/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RayQuery.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RayQuery.hh index 9a2f58a62..ad0ae0c37 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RayQuery.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RayQuery.hh @@ -24,7 +24,7 @@ #include "gz/rendering/ogre2/Ogre2Object.hh" #include "gz/rendering/ogre2/Ogre2RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderEngine.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderEngine.hh index 8809e054f..8513defe3 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderEngine.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderEngine.hh @@ -40,7 +40,7 @@ namespace Ogre } } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderPass.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderPass.hh index 8b74ec5db..580b64c97 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderPass.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderPass.hh @@ -24,7 +24,7 @@ #include "gz/rendering/ogre2/Ogre2Includes.hh" #include "gz/rendering/ogre2/Ogre2Object.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTarget.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTarget.hh index 48bdc1da8..e34b0c092 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTarget.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTarget.hh @@ -34,7 +34,7 @@ namespace Ogre class Texture; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTargetMaterial.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTargetMaterial.hh index 34643df4a..b699ef3da 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTargetMaterial.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTargetMaterial.hh @@ -23,7 +23,7 @@ #include "gz/rendering/ogre2/Ogre2Includes.hh" #include "gz/rendering/ogre2/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh index b54a10999..75623844a 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh @@ -22,7 +22,7 @@ #include "gz/rendering/config.hh" #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh index f8a72d36f..f49ddb974 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh @@ -31,7 +31,7 @@ namespace Ogre class SceneManager; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2SelectionBuffer.hh b/ogre2/include/gz/rendering/ogre2/Ogre2SelectionBuffer.hh index 8c82ceeb4..3acbd2474 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2SelectionBuffer.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2SelectionBuffer.hh @@ -30,7 +30,7 @@ namespace Ogre class SceneManager; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Sensor.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Sensor.hh index f09062209..00141d7e0 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Sensor.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Sensor.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseSensor.hh" #include "gz/rendering/ogre2/Ogre2Node.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Storage.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Storage.hh index 649c73fe1..a3cb09b9e 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Storage.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Storage.hh @@ -28,7 +28,7 @@ #include "gz/rendering/ogre2/Ogre2Scene.hh" #include "gz/rendering/ogre2/Ogre2Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2ThermalCamera.hh b/ogre2/include/gz/rendering/ogre2/Ogre2ThermalCamera.hh index 47f2c03c7..48438bb6a 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2ThermalCamera.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2ThermalCamera.hh @@ -43,7 +43,7 @@ namespace Ogre class Viewport; } -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Visual.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Visual.hh index 4822d7bec..11ebc123a 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Visual.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Visual.hh @@ -21,7 +21,7 @@ #include "gz/rendering/ogre2/Ogre2Node.hh" #include "gz/rendering/ogre2/Ogre2RenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/src/Ogre2DepthCamera.cc b/ogre2/src/Ogre2DepthCamera.cc index 8fbbe2ef7..838e1a12c 100644 --- a/ogre2/src/Ogre2DepthCamera.cc +++ b/ogre2/src/Ogre2DepthCamera.cc @@ -38,7 +38,7 @@ #include "gz/rendering/ogre2/Ogre2Sensor.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index 53df0e68f..57b36f4d9 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -33,7 +33,7 @@ #include "gz/rendering/ogre2/Ogre2Sensor.hh" #include "gz/rendering/ogre2/Ogre2Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index a0c816c7b..3740ec847 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -40,7 +40,7 @@ #include "gz/rendering/ogre2/Ogre2ThermalCamera.hh" #include "gz/rendering/ogre2/Ogre2Visual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixArrowVisual.hh b/optix/include/gz/rendering/optix/OptixArrowVisual.hh index 8e00a22d1..260fa8dad 100644 --- a/optix/include/gz/rendering/optix/OptixArrowVisual.hh +++ b/optix/include/gz/rendering/optix/OptixArrowVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseArrowVisual.hh" #include "gz/rendering/optix/OptixVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixAxisVisual.hh b/optix/include/gz/rendering/optix/OptixAxisVisual.hh index 805105327..37f93f619 100644 --- a/optix/include/gz/rendering/optix/OptixAxisVisual.hh +++ b/optix/include/gz/rendering/optix/OptixAxisVisual.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseAxisVisual.hh" #include "gz/rendering/optix/OptixVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixBox.hh b/optix/include/gz/rendering/optix/OptixBox.hh index 7c4714e88..872173cfb 100644 --- a/optix/include/gz/rendering/optix/OptixBox.hh +++ b/optix/include/gz/rendering/optix/OptixBox.hh @@ -19,7 +19,7 @@ #include "gz/rendering/optix/OptixPrimitive.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixCamera.hh b/optix/include/gz/rendering/optix/OptixCamera.hh index ea989d025..5ac597500 100644 --- a/optix/include/gz/rendering/optix/OptixCamera.hh +++ b/optix/include/gz/rendering/optix/OptixCamera.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixRenderTypes.hh" #include "gz/rendering/optix/OptixSensor.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixCone.hh b/optix/include/gz/rendering/optix/OptixCone.hh index 6ca32b9c6..d3a4d6352 100644 --- a/optix/include/gz/rendering/optix/OptixCone.hh +++ b/optix/include/gz/rendering/optix/OptixCone.hh @@ -19,7 +19,7 @@ #include "gz/rendering/optix/OptixPrimitive.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixConversions.hh b/optix/include/gz/rendering/optix/OptixConversions.hh index 065b3384f..bc6ac6a91 100644 --- a/optix/include/gz/rendering/optix/OptixConversions.hh +++ b/optix/include/gz/rendering/optix/OptixConversions.hh @@ -25,7 +25,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixCylinder.hh b/optix/include/gz/rendering/optix/OptixCylinder.hh index f9fc767f8..08ac588fc 100644 --- a/optix/include/gz/rendering/optix/OptixCylinder.hh +++ b/optix/include/gz/rendering/optix/OptixCylinder.hh @@ -19,7 +19,7 @@ #include "gz/rendering/optix/OptixPrimitive.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixGeometry.hh b/optix/include/gz/rendering/optix/OptixGeometry.hh index fbdec650e..1f5b2b029 100644 --- a/optix/include/gz/rendering/optix/OptixGeometry.hh +++ b/optix/include/gz/rendering/optix/OptixGeometry.hh @@ -21,7 +21,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/OptixObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixGrid.hh b/optix/include/gz/rendering/optix/OptixGrid.hh index 1631540c6..9adbaf707 100644 --- a/optix/include/gz/rendering/optix/OptixGrid.hh +++ b/optix/include/gz/rendering/optix/OptixGrid.hh @@ -24,7 +24,7 @@ #include "gz/rendering/optix/OptixObject.hh" #include "gz/rendering/optix/OptixRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixLight.hh b/optix/include/gz/rendering/optix/OptixLight.hh index 451994b75..cfc519a3d 100644 --- a/optix/include/gz/rendering/optix/OptixLight.hh +++ b/optix/include/gz/rendering/optix/OptixLight.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/OptixLightTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixLightManager.hh b/optix/include/gz/rendering/optix/OptixLightManager.hh index 1d1a35633..36d321695 100644 --- a/optix/include/gz/rendering/optix/OptixLightManager.hh +++ b/optix/include/gz/rendering/optix/OptixLightManager.hh @@ -25,7 +25,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixLightTypes.hh b/optix/include/gz/rendering/optix/OptixLightTypes.hh index bbcba606d..bfbe04593 100644 --- a/optix/include/gz/rendering/optix/OptixLightTypes.hh +++ b/optix/include/gz/rendering/optix/OptixLightTypes.hh @@ -20,7 +20,7 @@ #include #ifndef __CUDA_ARCH__ -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixMaterial.hh b/optix/include/gz/rendering/optix/OptixMaterial.hh index f333de231..1caa50378 100644 --- a/optix/include/gz/rendering/optix/OptixMaterial.hh +++ b/optix/include/gz/rendering/optix/OptixMaterial.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixObject.hh" #include "gz/rendering/optix/OptixIncludes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixMesh.hh b/optix/include/gz/rendering/optix/OptixMesh.hh index d7e77335e..a9c777029 100644 --- a/optix/include/gz/rendering/optix/OptixMesh.hh +++ b/optix/include/gz/rendering/optix/OptixMesh.hh @@ -24,7 +24,7 @@ #include "gz/rendering/optix/OptixObject.hh" #include "gz/rendering/optix/OptixRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixMeshFactory.hh b/optix/include/gz/rendering/optix/OptixMeshFactory.hh index ea8ff688e..fc0681a1a 100644 --- a/optix/include/gz/rendering/optix/OptixMeshFactory.hh +++ b/optix/include/gz/rendering/optix/OptixMeshFactory.hh @@ -26,7 +26,7 @@ #include "gz/rendering/optix/OptixMesh.hh" #include "gz/rendering/optix/OptixIncludes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixNode.hh b/optix/include/gz/rendering/optix/OptixNode.hh index 2a4089948..5deb803e9 100644 --- a/optix/include/gz/rendering/optix/OptixNode.hh +++ b/optix/include/gz/rendering/optix/OptixNode.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixRenderTypes.hh" #include "gz/rendering/optix/OptixObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixObject.hh b/optix/include/gz/rendering/optix/OptixObject.hh index a76f339c5..6ff746085 100644 --- a/optix/include/gz/rendering/optix/OptixObject.hh +++ b/optix/include/gz/rendering/optix/OptixObject.hh @@ -21,7 +21,7 @@ #include "gz/rendering/optix/OptixRenderTypes.hh" #include "gz/rendering/optix/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixPrimitive.hh b/optix/include/gz/rendering/optix/OptixPrimitive.hh index 81c8ef42e..649690aa2 100644 --- a/optix/include/gz/rendering/optix/OptixPrimitive.hh +++ b/optix/include/gz/rendering/optix/OptixPrimitive.hh @@ -20,7 +20,7 @@ #include #include "gz/rendering/optix/OptixGeometry.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixRayTypes.hh b/optix/include/gz/rendering/optix/OptixRayTypes.hh index bd696a2fa..b46c1ccf6 100644 --- a/optix/include/gz/rendering/optix/OptixRayTypes.hh +++ b/optix/include/gz/rendering/optix/OptixRayTypes.hh @@ -20,7 +20,7 @@ #include #ifndef __CUDA_ARCH__ -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixRenderEngine.hh b/optix/include/gz/rendering/optix/OptixRenderEngine.hh index 0f9b49fef..05635a883 100644 --- a/optix/include/gz/rendering/optix/OptixRenderEngine.hh +++ b/optix/include/gz/rendering/optix/OptixRenderEngine.hh @@ -25,7 +25,7 @@ #include "gz/rendering/base/BaseRenderEngine.hh" #include "gz/rendering/optix/OptixRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixRenderTarget.hh b/optix/include/gz/rendering/optix/OptixRenderTarget.hh index 3a96344cf..5beffe443 100644 --- a/optix/include/gz/rendering/optix/OptixRenderTarget.hh +++ b/optix/include/gz/rendering/optix/OptixRenderTarget.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixRenderTypes.hh" #include "gz/rendering/optix/OptixObject.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixRenderTypes.hh b/optix/include/gz/rendering/optix/OptixRenderTypes.hh index aceef798d..12202c74f 100644 --- a/optix/include/gz/rendering/optix/OptixRenderTypes.hh +++ b/optix/include/gz/rendering/optix/OptixRenderTypes.hh @@ -19,7 +19,7 @@ #include "gz/rendering/base/BaseRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixScene.hh b/optix/include/gz/rendering/optix/OptixScene.hh index bba2fcd88..6f94fcff4 100644 --- a/optix/include/gz/rendering/optix/OptixScene.hh +++ b/optix/include/gz/rendering/optix/OptixScene.hh @@ -25,7 +25,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixSensor.hh b/optix/include/gz/rendering/optix/OptixSensor.hh index 18378ef03..7d3f2dc0f 100644 --- a/optix/include/gz/rendering/optix/OptixSensor.hh +++ b/optix/include/gz/rendering/optix/OptixSensor.hh @@ -20,7 +20,7 @@ #include "gz/rendering/base/BaseSensor.hh" #include "gz/rendering/optix/OptixNode.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixSphere.hh b/optix/include/gz/rendering/optix/OptixSphere.hh index 85f8282bd..9b3092413 100644 --- a/optix/include/gz/rendering/optix/OptixSphere.hh +++ b/optix/include/gz/rendering/optix/OptixSphere.hh @@ -19,7 +19,7 @@ #include "gz/rendering/optix/OptixPrimitive.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixStorage.hh b/optix/include/gz/rendering/optix/OptixStorage.hh index c44789aec..0e4fddd21 100644 --- a/optix/include/gz/rendering/optix/OptixStorage.hh +++ b/optix/include/gz/rendering/optix/OptixStorage.hh @@ -28,7 +28,7 @@ #include "gz/rendering/optix/OptixSensor.hh" #include "gz/rendering/optix/OptixVisual.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixTextureFactory.hh b/optix/include/gz/rendering/optix/OptixTextureFactory.hh index a8506d02d..62b1f3b47 100644 --- a/optix/include/gz/rendering/optix/OptixTextureFactory.hh +++ b/optix/include/gz/rendering/optix/OptixTextureFactory.hh @@ -22,7 +22,7 @@ #include "gz/rendering/optix/OptixIncludes.hh" #include "gz/rendering/optix/Export.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/optix/include/gz/rendering/optix/OptixVisual.hh b/optix/include/gz/rendering/optix/OptixVisual.hh index d117a1874..990427f22 100644 --- a/optix/include/gz/rendering/optix/OptixVisual.hh +++ b/optix/include/gz/rendering/optix/OptixVisual.hh @@ -21,7 +21,7 @@ #include "gz/rendering/optix/OptixNode.hh" #include "gz/rendering/optix/OptixRenderTypes.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/src/RenderingIface.cc b/src/RenderingIface.cc index 45fb3d312..48b6727ce 100644 --- a/src/RenderingIface.cc +++ b/src/RenderingIface.cc @@ -22,7 +22,7 @@ #include "gz/rendering/RenderEngineManager.hh" #include "gz/rendering/Scene.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/src/Utils.cc b/src/Utils.cc index 91ebb6c95..08e00cb67 100644 --- a/src/Utils.cc +++ b/src/Utils.cc @@ -28,7 +28,7 @@ #include "gz/rendering/RayQuery.hh" #include "gz/rendering/Utils.hh" -namespace gz +namespace ignition { namespace rendering { diff --git a/test/test_config.h.in b/test/test_config.h.in index 645f8a69a..d75a726ef 100644 --- a/test/test_config.h.in +++ b/test/test_config.h.in @@ -14,7 +14,7 @@ static const std::vector kRenderEngineTestValues{"ogre2", "optix"} #include #include -namespace gz +namespace ignition { namespace rendering {