Skip to content

Commit c4a4539

Browse files
Ace314159JafarAbdinkalupahanajrgnichohenningkayser
authored
Fixes for Windows (#530)
Co-authored-by: JafarAbdi <[email protected]> Co-authored-by: Nisala Kalupahana <[email protected]> Co-authored-by: Jorge Nicho <[email protected]> Co-authored-by: Henning Kayser <[email protected]> Co-authored-by: Vatan Aksoy Tezer <[email protected]> Co-authored-by: Tyler Weaver <[email protected]> Co-authored-by: Lior Lustgarten <[email protected]>
1 parent 8112941 commit c4a4539

File tree

43 files changed

+167
-49
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+167
-49
lines changed

moveit_core/CMakeLists.txt

+7-7
Original file line numberDiff line numberDiff line change
@@ -13,17 +13,17 @@ find_package(Eigen3 REQUIRED)
1313
# Finds Boost Components
1414
include(ConfigExtras.cmake)
1515

16-
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules")
17-
18-
find_package(Bullet 2.87 REQUIRED)
19-
2016
find_package(PkgConfig REQUIRED)
21-
2217
pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
23-
# replace LIBFCL_LIBRARIES with full path to the library
24-
find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS})
18+
# replace LIBFCL_LIBRARIES with full paths to the libraries
19+
set(LIBFCL_LIBRARIES_FULL "")
20+
foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES})
21+
find_library(${LIBFCL_LIBRARY}_LIB ${LIBFCL_LIBRARY} ${LIBFCL_LIBRARY_DIRS})
22+
list(APPEND LIBFCL_LIBRARIES_FULL ${${LIBFCL_LIBRARY}_LIB})
23+
endforeach()
2524
set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}")
2625

26+
find_package(Bullet 2.87 REQUIRED)
2727
find_package(angles REQUIRED)
2828
find_package(OCTOMAP REQUIRED)
2929
find_package(urdfdom REQUIRED)

moveit_core/CMakeModules/FindBULLET.cmake

-10
This file was deleted.

moveit_core/ConfigExtras.cmake

-5
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,5 @@
11
# Extras module needed for dependencies to find boost components
22

3-
# boost::iostreams on Windows depends on boost::zlib
4-
if(WIN32)
5-
set(EXTRA_BOOST_COMPONENTS zlib)
6-
endif()
73
find_package(Boost REQUIRED
84
chrono
95
date_time
@@ -14,5 +10,4 @@ find_package(Boost REQUIRED
1410
serialization
1511
system
1612
thread
17-
${EXTRA_BOOST_COMPONENTS}
1813
)

moveit_core/collision_detection/CMakeLists.txt

+4-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
1010
src/world_diff.cpp
1111
src/collision_env.cpp
1212
)
13-
13+
include(GenerateExportHeader)
14+
generate_export_header(${MOVEIT_LIB_NAME})
15+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
1416
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
1517
ament_target_dependencies(${MOVEIT_LIB_NAME}
1618
rclcpp
@@ -51,3 +53,4 @@ if(BUILD_TESTING)
5153
endif()
5254

5355
install(DIRECTORY include/ DESTINATION include)
56+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)

moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,12 @@
3939
#include <moveit/collision_detection/collision_detector_allocator.h>
4040
#include <moveit/collision_detection/allvalid/collision_env_allvalid.h>
4141

42+
#include "moveit_collision_detection_export.h"
43+
4244
namespace collision_detection
4345
{
4446
/** \brief An allocator for AllValid collision detectors */
45-
class CollisionDetectorAllocatorAllValid
47+
class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid
4648
: public CollisionDetectorAllocatorTemplate<CollisionEnvAllValid, CollisionDetectorAllocatorAllValid>
4749
{
4850
public:

moveit_core/collision_detection_bullet/CMakeLists.txt

+13-3
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
99
src/bullet_integration/contact_checker_common.cpp
1010
src/bullet_integration/ros_bullet_utils.cpp
1111
)
12+
include(GenerateExportHeader)
13+
generate_export_header(${MOVEIT_LIB_NAME})
14+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
1215
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
1316
ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM
1417
BULLET
@@ -44,6 +47,7 @@ target_link_libraries(collision_detector_bullet_plugin
4447
)
4548

4649
install(DIRECTORY include/ DESTINATION include)
50+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
4751
install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME}
4852
TARGETS collision_detector_bullet_plugin EXPORT collision_detector_bullet_plugin
4953
LIBRARY DESTINATION lib
@@ -61,15 +65,21 @@ if(BUILD_TESTING)
6165
ament_add_gtest(test_bullet_collision_detection test/test_bullet_collision_detection_pr2.cpp)
6266
target_link_libraries(test_bullet_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME})
6367
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
64-
target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations)
68+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
69+
target_compile_options(test_bullet_collision_detection PRIVATE -Wno-deprecated-declarations)
70+
endif()
6571

6672
ament_add_gtest(test_bullet_collision_detection_panda test/test_bullet_collision_detection_panda.cpp)
6773
target_link_libraries(test_bullet_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME})
6874
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
69-
target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
75+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
76+
target_compile_options(test_bullet_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
77+
endif()
7078

7179
ament_add_gtest(test_bullet_continuous_collision_checking test/test_bullet_continuous_collision_checking.cpp)
7280
target_link_libraries(test_bullet_continuous_collision_checking moveit_test_utils ${MOVEIT_LIB_NAME})
7381
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
74-
target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations)
82+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
83+
target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations)
84+
endif()
7585
endif()

moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_detector_allocator_bullet.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,12 @@
3939
#include <moveit/collision_detection/collision_detector_allocator.h>
4040
#include <moveit/collision_detection_bullet/collision_env_bullet.h>
4141

42+
#include "moveit_collision_detection_bullet_export.h"
43+
4244
namespace collision_detection
4345
{
4446
/** \brief An allocator for Bullet collision detectors */
45-
class CollisionDetectorAllocatorBullet
47+
class MOVEIT_COLLISION_DETECTION_BULLET_EXPORT CollisionDetectorAllocatorBullet
4648
: public CollisionDetectorAllocatorTemplate<CollisionEnvBullet, CollisionDetectorAllocatorBullet>
4749
{
4850
public:

moveit_core/collision_detection_fcl/CMakeLists.txt

+10-2
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
44
src/collision_common.cpp
55
src/collision_env_fcl.cpp
66
)
7+
include(GenerateExportHeader)
8+
generate_export_header(${MOVEIT_LIB_NAME})
9+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
710
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
811
ament_target_dependencies(${MOVEIT_LIB_NAME}
912
rclcpp
@@ -34,6 +37,7 @@ target_link_libraries(collision_detector_fcl_plugin
3437
)
3538

3639
install(DIRECTORY include/ DESTINATION include)
40+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
3741

3842
if(BUILD_TESTING)
3943
if(WIN32)
@@ -48,10 +52,14 @@ if(BUILD_TESTING)
4852
ament_add_gtest(test_fcl_collision_detection test/test_fcl_collision_detection_pr2.cpp)
4953
target_link_libraries(test_fcl_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME})
5054
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
51-
target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations)
55+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
56+
target_compile_options(test_fcl_collision_detection PRIVATE -Wno-deprecated-declarations)
57+
endif()
5258

5359
ament_add_gtest(test_fcl_collision_detection_panda test/test_fcl_collision_detection_panda.cpp)
5460
target_link_libraries(test_fcl_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME})
5561
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
56-
target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
62+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
63+
target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
64+
endif()
5765
endif()

moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,12 @@
3939
#include <moveit/collision_detection/collision_detector_allocator.h>
4040
#include <moveit/collision_detection_fcl/collision_env_fcl.h>
4141

42+
#include "moveit_collision_detection_fcl_export.h"
43+
4244
namespace collision_detection
4345
{
4446
/** \brief An allocator for FCL collision detectors */
45-
class CollisionDetectorAllocatorFCL
47+
class MOVEIT_COLLISION_DETECTION_FCL_EXPORT CollisionDetectorAllocatorFCL
4648
: public CollisionDetectorAllocatorTemplate<CollisionEnvFCL, CollisionDetectorAllocatorFCL>
4749
{
4850
public:

moveit_core/constraint_samplers/test/pr2_arm_ik.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -789,6 +789,6 @@ bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num)
789789
else
790790
jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]);
791791

792-
return not(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
792+
return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
793793
}
794794
} // namespace pr2_arm_kinematics

moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
#include <kdl_parser/kdl_parser.hpp>
3939
#include <tf2_kdl/tf2_kdl.h>
4040
#include <algorithm>
41+
#include <cmath>
4142

4243
#include <moveit/robot_model/robot_model.h>
4344
#include "pr2_arm_kinematics_plugin.h"
@@ -240,7 +241,7 @@ double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::J
240241
{
241242
distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
242243
}
243-
return sqrt(distance);
244+
return std::sqrt(distance);
244245
}
245246

246247
void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info)

moveit_core/kinematics_base/CMakeLists.txt

+4-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,9 @@ cmake_minimum_required(VERSION 3.5)
22
set(MOVEIT_LIB_NAME moveit_kinematics_base)
33

44
add_library(${MOVEIT_LIB_NAME} SHARED src/kinematics_base.cpp)
5-
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
5+
include(GenerateExportHeader)
6+
generate_export_header(${MOVEIT_LIB_NAME})
7+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
68

79
# This line is needed to ensure that messages are done being built before this is built
810
ament_target_dependencies(
@@ -17,3 +19,4 @@ ament_target_dependencies(
1719
)
1820

1921
install(DIRECTORY include/ DESTINATION include)
22+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)

moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@
4343
#include <boost/function.hpp>
4444
#include <string>
4545

46+
#include "moveit_kinematics_base_export.h"
47+
4648
namespace moveit
4749
{
4850
namespace core
@@ -140,7 +142,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W
140142
* @class KinematicsBase
141143
* @brief Provides an interface for kinematics solvers.
142144
*/
143-
class KinematicsBase
145+
class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
144146
{
145147
public:
146148
static const rclcpp::Logger LOGGER;

moveit_core/planning_scene/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,9 @@
11
set(MOVEIT_LIB_NAME moveit_planning_scene)
22

33
add_library(${MOVEIT_LIB_NAME} SHARED src/planning_scene.cpp)
4+
include(GenerateExportHeader)
5+
generate_export_header(${MOVEIT_LIB_NAME})
6+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
47
#TODO: Fix the versioning
58
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
69
ament_target_dependencies(${MOVEIT_LIB_NAME}
@@ -26,6 +29,7 @@ target_link_libraries(${MOVEIT_LIB_NAME}
2629
)
2730

2831
install(DIRECTORY include/ DESTINATION include)
32+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
2933

3034
if(BUILD_TESTING)
3135
find_package(ament_cmake_gtest REQUIRED)

moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h

+4-1
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,8 @@
5757
#include <memory>
5858
#include "rclcpp/rclcpp.hpp"
5959

60+
#include "moveit_planning_scene_export.h"
61+
6062
/** \brief This namespace includes the central class for representing planning contexts */
6163
namespace planning_scene
6264
{
@@ -85,7 +87,8 @@ using ObjectTypeMap = std::map<std::string, object_recognition_msgs::msg::Object
8587
/** \brief This class maintains the representation of the
8688
environment as seen by a planning instance. The environment
8789
geometry, the robot geometry and state are maintained. */
88-
class PlanningScene : private boost::noncopyable, public std::enable_shared_from_this<PlanningScene>
90+
class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : private boost::noncopyable,
91+
public std::enable_shared_from_this<PlanningScene>
8992
{
9093
public:
9194
/** \brief construct using an existing RobotModel */

moveit_core/robot_model/include/moveit/robot_model/joint_model.h

+2
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,8 @@
4545
#include <random_numbers/random_numbers.h>
4646
#include <Eigen/Geometry>
4747

48+
#undef near
49+
4850
namespace moveit
4951
{
5052
namespace core

moveit_ros/benchmarks/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -37,9 +37,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED
3737
src/BenchmarkExecutor.cpp
3838
)
3939
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
40+
if(WIN32)
41+
set(EXTRA_LIB ws2_32.lib)
42+
endif()
4043
ament_target_dependencies(${MOVEIT_LIB_NAME}
4144
${THIS_PACKAGE_INCLUDE_DEPENDS}
4245
)
46+
target_link_libraries(${MOVEIT_LIB_NAME} ${EXTRA_LIB})
4347

4448
add_executable(moveit_run_benchmark src/RunBenchmark.cpp)
4549
ament_target_dependencies(moveit_run_benchmark

moveit_ros/benchmarks/src/BenchmarkExecutor.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -49,12 +49,15 @@
4949
#include <boost/math/constants/constants.hpp>
5050
#include <boost/filesystem.hpp>
5151
#include <boost/date_time/posix_time/posix_time.hpp>
52+
#include <limits>
5253
#ifndef _WIN32
5354
#include <unistd.h>
5455
#else
5556
#include <winsock2.h>
5657
#endif
5758

59+
#undef max
60+
5861
using namespace moveit_ros_benchmarks;
5962

6063
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.benchmarks.BenchmarkExecutor");

moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -330,7 +330,7 @@ class ServoCalcs
330330

331331
const int gazebo_redundant_message_count_ = 30;
332332

333-
uint num_joints_;
333+
unsigned int num_joints_;
334334

335335
// True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw]
336336
std::array<bool, 6> drift_dimensions_ = { { false, false, false, false, false, false } };

moveit_ros/perception/CMakeLists.txt

+5-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,11 @@ if(WITH_OPENGL)
2828
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut)
2929
else()
3030
find_package(GLUT REQUIRED)
31-
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT)
31+
if(WIN32)
32+
set(SYSTEM_GL_LIBRARIES GLEW::glew GLUT::GLUT)
33+
else()
34+
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT)
35+
endif()
3236
endif()
3337
set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include")
3438
set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR})

moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include <stdint.h>
4545

4646
#include <memory>
47+
#include <boost/bind.hpp>
4748

4849
namespace occupancy_map_monitor
4950
{

moveit_ros/perception/mesh_filter/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
77
src/gl_renderer.cpp
88
src/gl_mesh.cpp
99
)
10+
include(GenerateExportHeader)
11+
generate_export_header(${MOVEIT_LIB_NAME})
12+
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
1013
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
1114
ament_target_dependencies(${MOVEIT_LIB_NAME}
1215
rclcpp
@@ -40,3 +43,4 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES})
4043
# endif()
4144

4245
install(DIRECTORY include/ DESTINATION include)
46+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)

moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h

+3
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,9 @@
4848
#include <mutex>
4949
#include <map>
5050

51+
#undef near
52+
#undef far
53+
5154
namespace mesh_filter
5255
{
5356
MOVEIT_CLASS_FORWARD(GLRenderer); // Defines GLRendererPtr, ConstPtr, WeakPtr... etc

moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,15 @@
3939
#include <moveit/mesh_filter/sensor_model.h>
4040
#include <string>
4141

42+
#include "moveit_mesh_filter_export.h"
43+
4244
namespace mesh_filter
4345
{
4446
/**
4547
* \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices
4648
* \author Suat Gedikli <[email protected]>
4749
*/
48-
class StereoCameraModel : public SensorModel
50+
class MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel
4951
{
5052
public:
5153
/**

0 commit comments

Comments
 (0)