Skip to content

Commit

Permalink
3 ➡️ 4 (#213)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jan 28, 2021
2 parents 27f9977 + 530014b commit a5f00f9
Show file tree
Hide file tree
Showing 73 changed files with 406 additions and 141 deletions.
2 changes: 1 addition & 1 deletion examples/actor_animation/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/camera_tracking/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
4 changes: 2 additions & 2 deletions examples/custom_scene_viewer/DemoWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@
#if defined(__APPLE__)
#include <OpenGL/gl.h>
#include <GLUT/glut.h>
#elif not defined(_WIN32)
#elif !defined(_WIN32)
#include <GL/glew.h>
#include <GL/gl.h>
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/gazebo_scene_viewer/CameraWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/mesh_viewer/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/mouse_picking/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/ogre2_demo/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/render_pass/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/simple_demo/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/text_geom/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/thermal_camera/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/transform_control/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/view_control/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
1 change: 0 additions & 1 deletion include/ignition/rendering/MeshDescriptor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ namespace ignition
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief common::Mesh object
public: const common::Mesh *mesh = nullptr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Name of the registered Mesh
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/rendering/RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef IGNITION_RENDERING_RAYQUERY_HH_
#define IGNITION_RENDERING_RAYQUERY_HH_

#include <ignition/common/SuppressWarning.hh>
#include <ignition/math/Vector3.hh>

#include "ignition/rendering/config.hh"
Expand All @@ -37,7 +38,9 @@ namespace ignition
public: double distance = -1;

/// \brief Intersection point in 3d space
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: math::Vector3d point;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Intersected object id
public: unsigned int objectId = 0;
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/RenderEnginePlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <memory>
#include <string>

#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Export.hh"

Expand Down Expand Up @@ -52,7 +54,9 @@ namespace ignition
public: virtual RenderEngine *Engine() const = 0;

/// \brief Pointer to private data class
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: std::unique_ptr<RenderEnginePluginPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/RenderPassSystem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <string>
#include <typeinfo>

#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Export.hh"
#include "ignition/rendering/RenderPass.hh"
Expand Down Expand Up @@ -78,11 +80,13 @@ namespace ignition
private: RenderPassPtr CreateImpl(const std::string &_type);

/// \brief A map of render pass type id name to its factory class
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
private: static std::map<std::string, RenderPassFactory *> renderPassMap;

/// \internal
/// \brief Pointer to private data class
private: std::unique_ptr<RenderPassSystemPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};

/// \brief Render pass registration macro
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/ShaderParam.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <cstdint>
#include <memory>

#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Export.hh"

Expand Down Expand Up @@ -86,7 +88,9 @@ namespace ignition
public: bool Value(int *_value) const;

/// \brief private implementation
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
private: std::unique_ptr<ShaderParamPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/TransformController.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <memory>

#include <ignition/common/SuppressWarning.hh>

#include <ignition/math/Quaternion.hh>
#include <ignition/math/Plane.hh>
#include <ignition/math/Vector3.hh>
Expand Down Expand Up @@ -210,7 +212,9 @@ namespace ignition
const math::Planed &_plane, math::Vector3d &_result);

/// \brief Private data pointer
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: std::unique_ptr<TransformControllerPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/rendering/base/BaseCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include <ignition/common/Event.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/Camera.hh"
#include "ignition/rendering/Image.hh"
Expand Down Expand Up @@ -185,6 +186,7 @@ namespace ignition

protected: virtual RenderTargetPtr RenderTarget() const = 0;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
protected: common::EventT<void(const void *, unsigned int, unsigned int,
unsigned int, const std::string &)> newFrameEvent;

Expand Down Expand Up @@ -221,6 +223,7 @@ namespace ignition

/// \brief Target node to follow
protected: NodePtr followNode;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Follow target in world frame.
protected: bool followWorldFrame = false;
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/rendering/base/BaseDepthCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace ignition
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
template <class T>
class IGNITION_RENDERING_VISIBLE BaseDepthCamera :
class BaseDepthCamera :
public virtual DepthCamera,
public virtual BaseCamera<T>,
public virtual T
Expand Down
15 changes: 12 additions & 3 deletions include/ignition/rendering/base/BaseGizmoVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <map>
#include <string>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/base/BaseScene.hh"
#include "ignition/rendering/base/BaseNode.hh"
Expand Down Expand Up @@ -92,6 +93,7 @@ namespace ignition
/// \brief Current gizmo mode
protected: TransformMode mode = TransformMode::TM_NONE;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief A map of gizmo axis and their visuals
protected: std::map<unsigned int, VisualPtr> visuals;

Expand All @@ -109,6 +111,7 @@ namespace ignition

/// \brief A map of axis enums to materials
protected: std::map<unsigned int, MaterialPtr> materials;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Material used by axes
protected: enum AxisMaterial
Expand Down Expand Up @@ -531,15 +534,21 @@ namespace ignition
common::MeshManager *meshMgr = common::MeshManager::Instance();
std::string rotMeshName = "gizmo_rotate";
if (!meshMgr->HasMesh(rotMeshName))
meshMgr->CreateTube(rotMeshName, 1.0, 1.02, 0.02, 1, 64, IGN_PI);
meshMgr->CreateTube(rotMeshName, 1.0f, 1.02f, 0.02f, 1, 64, IGN_PI);

std::string rotFullMeshName = "gizmo_rotate_full";
if (!meshMgr->HasMesh(rotFullMeshName))
meshMgr->CreateTube(rotFullMeshName, 1.0, 1.02, 0.02, 1, 64, 2*IGN_PI);
{
meshMgr->CreateTube(rotFullMeshName, 1.0f, 1.02f, 0.02f, 1, 64,
2 * IGN_PI);
}

std::string rotHandleMeshName = "gizmo_rotate_handle";
if (!meshMgr->HasMesh(rotHandleMeshName))
meshMgr->CreateTube(rotHandleMeshName, 0.95, 1.07, 0.1, 1, 64, IGN_PI);
{
meshMgr->CreateTube(rotHandleMeshName, 0.95f, 1.07f, 0.1f, 1, 64,
IGN_PI);
}

VisualPtr rotVis = this->Scene()->CreateVisual();

Expand Down
8 changes: 4 additions & 4 deletions include/ignition/rendering/base/BaseLidarVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -462,7 +462,7 @@ namespace ignition
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.0);
mtl->SetMetalness(0.0f);
mtl->SetReflectivity(0.0);
}

Expand All @@ -476,7 +476,7 @@ namespace ignition
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.0);
mtl->SetMetalness(0.0f);
mtl->SetReflectivity(0.0);
}

Expand All @@ -490,7 +490,7 @@ namespace ignition
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.5);
mtl->SetMetalness(0.5f);
mtl->SetReflectivity(0.2);
}

Expand All @@ -505,7 +505,7 @@ namespace ignition
mtl->SetCastShadows(false);
mtl->SetReceiveShadows(false);
mtl->SetLightingEnabled(false);
mtl->SetMetalness(0.1);
mtl->SetMetalness(0.1f);
mtl->SetReflectivity(0.2);
}
return;
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/base/BaseMarker.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#ifndef IGNITION_RENDERING_BASEMARKER_HH_
#define IGNITION_RENDERING_BASEMARKER_HH_

#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/Marker.hh"
#include "ignition/rendering/base/BaseObject.hh"
#include "ignition/rendering/base/BaseRenderTypes.hh"
Expand Down Expand Up @@ -81,8 +83,10 @@ namespace ignition
const ignition::math::Vector3d &_value) override;

/// \brief Life time of a marker
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
protected: std::chrono::steady_clock::duration lifetime =
std::chrono::steady_clock::duration::zero();
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Layer at which the marker will reside
protected: int32_t layer = 0;
Expand Down
5 changes: 5 additions & 0 deletions include/ignition/rendering/base/BaseObject.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <map>
#include <string>
#include <ignition/common/SuppressWarning.hh>
#include "ignition/rendering/Object.hh"

namespace ignition
Expand All @@ -28,7 +29,9 @@ namespace ignition
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
class IGNITION_RENDERING_VISIBLE BaseObject :
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public virtual std::enable_shared_from_this<BaseObject>,
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
public virtual Object
{
protected: BaseObject();
Expand Down Expand Up @@ -56,7 +59,9 @@ namespace ignition

protected: unsigned int id;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
protected: std::string name;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
Loading

0 comments on commit a5f00f9

Please sign in to comment.