-
-
Notifications
You must be signed in to change notification settings - Fork 74
/
Copy pathros-noetic-moveit-ros-perception.win.patch
128 lines (113 loc) · 5.22 KB
/
ros-noetic-moveit-ros-perception.win.patch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt
index 73f692e68..d17ed79d0 100644
--- a/moveit_ros/perception/CMakeLists.txt
+++ b/moveit_ros/perception/CMakeLists.txt
@@ -26,6 +26,9 @@ if(WITH_OPENGL)
set(gl_LIBS ${gl_LIBS} ${OPENGL_LIBRARIES})
set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include")
set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR})
+ if(TARGET GLEW::glew)
+ set(GLEW_LIBRARIES GLEW::glew)
+ endif()
endif(WITH_OPENGL)
if(APPLE)
@@ -18,6 +18,12 @@ if(WITH_OPENGL)
set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR})
endif(WITH_OPENGL)
+if(MSVC AND ${MSVC_VERSION} GREATER_EQUAL 1915)
+ # You must acknowledge that you understand MSVC resolved a byte alignment issue in this compiler
+ # We get this due to using Eigen objects and allocating those objects with make_shared
+ add_compile_definitions(_ENABLE_EXTENDED_ALIGNED_STORAGE)
+endif()
+
if(APPLE)
find_package(X11 REQUIRED)
endif(APPLE)
diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h
index 5ffd8174d..6445b8d37 100644
--- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h
+++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h
@@ -39,6 +39,18 @@
#include <moveit/mesh_filter/sensor_model.h>
#include <string>
+// Import/export for windows dll's and visibility for gcc shared libraries.
+
+#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
+ #ifdef moveit_mesh_filter_EXPORTS // we are building a shared lib/dll
+ #define MOVEIT_MESH_FILTER_DECL ROS_HELPER_EXPORT
+ #else // we are using shared lib/dll
+ #define MOVEIT_MESH_FILTER_DECL ROS_HELPER_IMPORT
+ #endif
+#else // ros is being built around static libraries
+ #define MOVEIT_MESH_FILTER_DECL
+#endif
+
namespace mesh_filter
{
/**
@@ -148,18 +160,18 @@ public:
};
/** \brief predefined sensor model for OpenNI compatible devices (e.g., PrimeSense, Kinect, Asus Xtion) */
- static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming)
+ MOVEIT_MESH_FILTER_DECL static const StereoCameraModel::Parameters& REGISTERED_PSDK_PARAMS; // NOLINT(readability-identifier-naming)
/** \brief source code of the vertex shader used to render the meshes*/
- static const std::string RENDER_VERTEX_SHADER_SOURCE;
+ MOVEIT_MESH_FILTER_DECL static const std::string RENDER_VERTEX_SHADER_SOURCE;
/** \brief source code of the fragment shader used to render the meshes*/
- static const std::string RENDER_FRAGMENT_SHADER_SOURCE;
+ MOVEIT_MESH_FILTER_DECL static const std::string RENDER_FRAGMENT_SHADER_SOURCE;
/** \brief source code of the vertex shader used to filter the depth map*/
- static const std::string FILTER_VERTEX_SHADER_SOURCE;
+ MOVEIT_MESH_FILTER_DECL static const std::string FILTER_VERTEX_SHADER_SOURCE;
/** \brief source code of the fragment shader used to filter the depth map*/
- static const std::string FILTER_FRAGMENT_SHADER_SOURCE;
+ MOVEIT_MESH_FILTER_DECL static const std::string FILTER_FRAGMENT_SHADER_SOURCE;
};
} // namespace mesh_filter
diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
index 4f351b53e..93086ba74 100644
--- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
+++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
@@ -52,7 +52,7 @@
using namespace std;
-mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, float near, float far)
+mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, float _near, float _far)
: width_(width)
, height_(height)
, fbo_id_(0)
@@ -60,8 +60,8 @@ mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, float near,
, rgb_id_(0)
, depth_id_(0)
, program_(0)
- , near_(near)
- , far_(far)
+ , near_(_near)
+ , far_(_far)
, fx_(width >> 1) // 90 degree wide angle
, fy_(fx_)
, cx_(width >> 1)
@@ -89,14 +89,14 @@ void mesh_filter::GLRenderer::setBufferSize(unsigned width, unsigned height)
}
}
-void mesh_filter::GLRenderer::setClippingRange(float near, float far)
+void mesh_filter::GLRenderer::setClippingRange(float _near, float _far)
{
if (near_ <= 0)
throw runtime_error("near clipping plane distance needs to be larger than 0");
if (far_ <= near_)
throw runtime_error("far clipping plane needs to be larger than near clipping plane distance");
- near_ = near;
- far_ = far;
+ near_ = _near;
+ far_ = _far;
}
void mesh_filter::GLRenderer::setCameraParameters(float fx, float fy, float cx, float cy)
diff --git a/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp b/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp
index 5881faffd..7ae0d76b0 100644
--- a/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp
+++ b/moveit_ros/perception/mesh_filter/src/stereo_camera_model.cpp
@@ -34,6 +34,7 @@
/* Author: Suat Gedikli */
+#include <ros/ros.h>
#include <moveit/mesh_filter/stereo_camera_model.h>
#include <moveit/mesh_filter/gl_renderer.h>