Skip to content

Commit

Permalink
Try all of moveit on Win
Browse files Browse the repository at this point in the history
  • Loading branch information
Tobias-Fischer committed Oct 2, 2020
1 parent 8b5a539 commit 1b98122
Show file tree
Hide file tree
Showing 10 changed files with 551 additions and 5 deletions.
14 changes: 14 additions & 0 deletions patch/ros-noetic-moveit-ros-benchmarks.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 0eb7714e8..9cf8c6a2f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -41,6 +41,9 @@ add_library(${MOVEIT_LIB_NAME} src/BenchmarkOptions.cpp
src/BenchmarkExecutor.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
+if(WIN32)
+ target_link_libraries(${MOVEIT_LIB_NAME} ws2_32)
+endif()

add_executable(moveit_run_benchmark src/RunBenchmark.cpp)
target_link_libraries(moveit_run_benchmark ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
34 changes: 34 additions & 0 deletions patch/ros-noetic-moveit-ros-manipulation.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
diff --git a/pick_place/include/moveit/pick_place/pick_place.h b/pick_place/include/moveit/pick_place/pick_place.h
index 6c2118562..ec804cab5 100644
--- a/pick_place/include/moveit/pick_place/pick_place.h
+++ b/pick_place/include/moveit/pick_place/pick_place.h
@@ -46,6 +46,18 @@
#include <boost/noncopyable.hpp>
#include <memory>

+// 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_pick_place_planner_EXPORTS // we are building a shared lib/dll
+ #define MOVEIT_PICK_PLACE_DECL ROS_HELPER_EXPORT
+ #else // we are using shared lib/dll
+ #define MOVEIT_PICK_PLACE_DECL ROS_HELPER_IMPORT
+ #endif
+#else // ros is being built around static libraries
+ #define MOVEIT_PICK_PLACE_DECL
+#endif
+
namespace pick_place
{
MOVEIT_CLASS_FORWARD(PickPlace);
@@ -113,8 +125,8 @@ public:
class PickPlace : private boost::noncopyable, public std::enable_shared_from_this<PickPlace>
{
public:
- static const std::string DISPLAY_PATH_TOPIC;
- static const std::string DISPLAY_GRASP_TOPIC;
+ static MOVEIT_PICK_PLACE_DECL const std::string DISPLAY_PATH_TOPIC;
+ static MOVEIT_PICK_PLACE_DECL const std::string DISPLAY_GRASP_TOPIC;

// the amount of time (maximum) to wait for achieving a grasp posture
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION; // seconds
115 changes: 115 additions & 0 deletions patch/ros-noetic-moveit-ros-perception.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
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)
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>

73 changes: 73 additions & 0 deletions patch/ros-noetic-moveit-ros-planning-interface.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index bcc6070c8..78c0637bf 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -28,6 +28,9 @@ find_package(catkin REQUIRED COMPONENTS
rosconsole
)

+find_package(PkgConfig REQUIRED)
+pkg_check_modules(EIGENPY REQUIRED eigenpy)
+
find_package(PythonInterp REQUIRED)
find_package(PythonLibs "${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" REQUIRED)

@@ -88,8 +91,11 @@ include_directories(SYSTEM
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
+ ${EIGENPY_INCLUDE_DIRS}
${PYTHON_INCLUDE_DIRS})

+link_directories(${EIGENPY_LIBRARY_DIRS})
+
add_subdirectory(py_bindings_tools)
add_subdirectory(common_planning_interface_objects)
add_subdirectory(planning_scene_interface)
diff --git a/move_group_interface/CMakeLists.txt b/move_group_interface/CMakeLists.txt
index d822174bf..c3eb1686c 100644
--- a/move_group_interface/CMakeLists.txt
+++ b/move_group_interface/CMakeLists.txt
@@ -2,7 +2,7 @@ set(MOVEIT_LIB_NAME moveit_move_group_interface)

add_library(${MOVEIT_LIB_NAME} src/move_group_interface.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
-target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${catkin_LIBRARIES} ${Boost_LIBRARIES})
+target_link_libraries(${MOVEIT_LIB_NAME} moveit_common_planning_interface_objects moveit_planning_scene_interface ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${EIGENPY_LIBRARIES})
add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS})

add_library(${MOVEIT_LIB_NAME}_python src/wrap_python_move_group.cpp)
diff --git a/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/move_group_interface/include/moveit/move_group_interface/move_group_interface.h
index ec8d70f0b..0e8c6b340 100644
--- a/move_group_interface/include/moveit/move_group_interface/move_group_interface.h
+++ b/move_group_interface/include/moveit/move_group_interface/move_group_interface.h
@@ -55,6 +55,20 @@
#include <utility>
#include <tf2_ros/buffer.h>

+#include <ros/macros.h>
+
+// 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_move_group_interface_EXPORTS // we are building a shared lib/dll
+ #define MOVEIT_MOVE_GROUP_INTERFACE_DECL ROS_HELPER_EXPORT
+ #else // we are using shared lib/dll
+ #define MOVEIT_MOVE_GROUP_INTERFACE_DECL ROS_HELPER_IMPORT
+ #endif
+#else // ros is being built around static libraries
+ #define MOVEIT_MOVE_GROUP_INTERFACE_DECL
+#endif
+
namespace moveit
{
/** \brief Simple interface to MoveIt components */
@@ -96,7 +110,7 @@ MOVEIT_CLASS_FORWARD(MoveGroupInterface);
\brief Client class to conveniently use the ROS interfaces provided by the move_group node.

This class includes many default settings to make things easy to use. */
-class MoveGroupInterface
+class MOVEIT_MOVE_GROUP_INTERFACE_DECL MoveGroupInterface
{
public:
/** \brief Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description' */
35 changes: 35 additions & 0 deletions patch/ros-noetic-moveit-ros-robot-interaction.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h
index 40ebd87d1..8d7a8972a 100644
--- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h
+++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h
@@ -40,6 +40,18 @@
#include <boost/thread.hpp>
#include <boost/function.hpp>

+// 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_robot_interaction_EXPORTS // we are building a shared lib/dll
+ #define MOVEIT_ROBOT_INTERACTION_DECL ROS_HELPER_EXPORT
+ #else // we are using shared lib/dll
+ #define MOVEIT_ROBOT_INTERACTION_DECL ROS_HELPER_IMPORT
+ #endif
+#else // ros is being built around static libraries
+ #define MOVEIT_ROBOT_INTERACTION_DECL
+#endif
+
namespace robot_interaction
{
// Maintains a set of KinematicOptions with a key/value mapping and a default
@@ -51,10 +63,10 @@ public:
KinematicOptionsMap();

/// When used as \e key this means the default value
- static const std::string DEFAULT;
+ static MOVEIT_ROBOT_INTERACTION_DECL const std::string DEFAULT;

/// When used as \e key this means set ALL keys (including default)
- static const std::string ALL;
+ static MOVEIT_ROBOT_INTERACTION_DECL const std::string ALL;

/// Set \e state using inverse kinematics.
35 changes: 35 additions & 0 deletions patch/ros-noetic-moveit-ros-visualization.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
/// @param state the state to set
diff --git a/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h
index 99f9ab863..69ce6a7c1 100644
--- a/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h
+++ b/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h
@@ -45,6 +45,20 @@
#include <ros/ros.h>
#endif

+#include <ros/macros.h>
+
+// 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_planning_scene_rviz_plugin_core_EXPORTS // we are building a shared lib/dll
+ #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_DECL ROS_HELPER_EXPORT
+ #else // we are using shared lib/dll
+ #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_DECL ROS_HELPER_IMPORT
+ #endif
+#else // ros is being built around static libraries
+ #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_DECL
+#endif
+
namespace Ogre
{
class SceneNode;
@@ -64,7 +78,7 @@ class EnumProperty;

namespace moveit_rviz_plugin
{
-class PlanningSceneDisplay : public rviz::Display
+class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_DECL PlanningSceneDisplay : public rviz::Display
{
Q_OBJECT

Loading

0 comments on commit 1b98122

Please sign in to comment.