Skip to content

Commit

Permalink
Fixes for Windows (moveit#530)
Browse files Browse the repository at this point in the history
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]>
  • Loading branch information
8 people authored and christianlandgraf committed Aug 12, 2021
1 parent 4003d22 commit ad19978
Show file tree
Hide file tree
Showing 43 changed files with 167 additions and 49 deletions.
14 changes: 7 additions & 7 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,17 @@ find_package(Eigen3 REQUIRED)
# Finds Boost Components
include(ConfigExtras.cmake)

list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules")

find_package(Bullet 2.87 REQUIRED)

find_package(PkgConfig REQUIRED)

pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
# replace LIBFCL_LIBRARIES with full path to the library
find_library(LIBFCL_LIBRARIES_FULL ${LIBFCL_LIBRARIES} ${LIBFCL_LIBRARY_DIRS})
# replace LIBFCL_LIBRARIES with full paths to the libraries
set(LIBFCL_LIBRARIES_FULL "")
foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES})
find_library(${LIBFCL_LIBRARY}_LIB ${LIBFCL_LIBRARY} ${LIBFCL_LIBRARY_DIRS})
list(APPEND LIBFCL_LIBRARIES_FULL ${${LIBFCL_LIBRARY}_LIB})
endforeach()
set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}")

find_package(Bullet 2.87 REQUIRED)
find_package(angles REQUIRED)
find_package(OCTOMAP REQUIRED)
find_package(urdfdom REQUIRED)
Expand Down
10 changes: 0 additions & 10 deletions moveit_core/CMakeModules/FindBULLET.cmake

This file was deleted.

5 changes: 0 additions & 5 deletions moveit_core/ConfigExtras.cmake
Original file line number Diff line number Diff line change
@@ -1,9 +1,5 @@
# Extras module needed for dependencies to find boost components

# boost::iostreams on Windows depends on boost::zlib
if(WIN32)
set(EXTRA_BOOST_COMPONENTS zlib)
endif()
find_package(Boost REQUIRED
chrono
date_time
Expand All @@ -14,5 +10,4 @@ find_package(Boost REQUIRED
serialization
system
thread
${EXTRA_BOOST_COMPONENTS}
)
5 changes: 4 additions & 1 deletion moveit_core/collision_detection/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/world_diff.cpp
src/collision_env.cpp
)

include(GenerateExportHeader)
generate_export_header(${MOVEIT_LIB_NAME})
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
Expand Down Expand Up @@ -51,3 +53,4 @@ if(BUILD_TESTING)
endif()

install(DIRECTORY include/ DESTINATION include)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,12 @@
#include <moveit/collision_detection/collision_detector_allocator.h>
#include <moveit/collision_detection/allvalid/collision_env_allvalid.h>

#include "moveit_collision_detection_export.h"

namespace collision_detection
{
/** \brief An allocator for AllValid collision detectors */
class CollisionDetectorAllocatorAllValid
class MOVEIT_COLLISION_DETECTION_EXPORT CollisionDetectorAllocatorAllValid
: public CollisionDetectorAllocatorTemplate<CollisionEnvAllValid, CollisionDetectorAllocatorAllValid>
{
public:
Expand Down
16 changes: 13 additions & 3 deletions moveit_core/collision_detection_bullet/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/bullet_integration/contact_checker_common.cpp
src/bullet_integration/ros_bullet_utils.cpp
)
include(GenerateExportHeader)
generate_export_header(${MOVEIT_LIB_NAME})
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
ament_target_dependencies(${MOVEIT_LIB_NAME} SYSTEM
BULLET
Expand Down Expand Up @@ -44,6 +47,7 @@ target_link_libraries(collision_detector_bullet_plugin
)

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

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

ament_add_gtest(test_bullet_continuous_collision_checking test/test_bullet_continuous_collision_checking.cpp)
target_link_libraries(test_bullet_continuous_collision_checking moveit_test_utils ${MOVEIT_LIB_NAME})
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
target_compile_options(test_bullet_continuous_collision_checking PRIVATE -Wno-deprecated-declarations)
endif()
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,12 @@
#include <moveit/collision_detection/collision_detector_allocator.h>
#include <moveit/collision_detection_bullet/collision_env_bullet.h>

#include "moveit_collision_detection_bullet_export.h"

namespace collision_detection
{
/** \brief An allocator for Bullet collision detectors */
class CollisionDetectorAllocatorBullet
class MOVEIT_COLLISION_DETECTION_BULLET_EXPORT CollisionDetectorAllocatorBullet
: public CollisionDetectorAllocatorTemplate<CollisionEnvBullet, CollisionDetectorAllocatorBullet>
{
public:
Expand Down
12 changes: 10 additions & 2 deletions moveit_core/collision_detection_fcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/collision_common.cpp
src/collision_env_fcl.cpp
)
include(GenerateExportHeader)
generate_export_header(${MOVEIT_LIB_NAME})
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
Expand Down Expand Up @@ -34,6 +37,7 @@ target_link_libraries(collision_detector_fcl_plugin
)

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

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

ament_add_gtest(test_fcl_collision_detection_panda test/test_fcl_collision_detection_panda.cpp)
target_link_libraries(test_fcl_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME})
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
target_compile_options(test_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
endif()
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,12 @@
#include <moveit/collision_detection/collision_detector_allocator.h>
#include <moveit/collision_detection_fcl/collision_env_fcl.h>

#include "moveit_collision_detection_fcl_export.h"

namespace collision_detection
{
/** \brief An allocator for FCL collision detectors */
class CollisionDetectorAllocatorFCL
class MOVEIT_COLLISION_DETECTION_FCL_EXPORT CollisionDetectorAllocatorFCL
: public CollisionDetectorAllocatorTemplate<CollisionEnvFCL, CollisionDetectorAllocatorFCL>
{
public:
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/constraint_samplers/test/pr2_arm_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -789,6 +789,6 @@ bool PR2ArmIK::checkJointLimits(const double& joint_value, const int& joint_num)
else
jv = angles::normalize_angle(joint_value * angle_multipliers_[joint_num]);

return not(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
return !(jv < min_angles_[joint_num] || jv > max_angles_[joint_num]);
}
} // namespace pr2_arm_kinematics
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <kdl_parser/kdl_parser.hpp>
#include <tf2_kdl/tf2_kdl.h>
#include <algorithm>
#include <cmath>

#include <moveit/robot_model/robot_model.h>
#include "pr2_arm_kinematics_plugin.h"
Expand Down Expand Up @@ -240,7 +241,7 @@ double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::J
{
distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
}
return sqrt(distance);
return std::sqrt(distance);
}

void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info)
Expand Down
5 changes: 4 additions & 1 deletion moveit_core/kinematics_base/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,9 @@ cmake_minimum_required(VERSION 3.5)
set(MOVEIT_LIB_NAME moveit_kinematics_base)

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

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

install(DIRECTORY include/ DESTINATION include)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#include <boost/function.hpp>
#include <string>

#include "moveit_kinematics_base_export.h"

namespace moveit
{
namespace core
Expand Down Expand Up @@ -140,7 +142,7 @@ MOVEIT_CLASS_FORWARD(KinematicsBase); // Defines KinematicsBasePtr, ConstPtr, W
* @class KinematicsBase
* @brief Provides an interface for kinematics solvers.
*/
class KinematicsBase
class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
{
public:
static const rclcpp::Logger LOGGER;
Expand Down
4 changes: 4 additions & 0 deletions moveit_core/planning_scene/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
set(MOVEIT_LIB_NAME moveit_planning_scene)

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

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

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@
#include <memory>
#include "rclcpp/rclcpp.hpp"

#include "moveit_planning_scene_export.h"

/** \brief This namespace includes the central class for representing planning contexts */
namespace planning_scene
{
Expand Down Expand Up @@ -85,7 +87,8 @@ using ObjectTypeMap = std::map<std::string, object_recognition_msgs::msg::Object
/** \brief This class maintains the representation of the
environment as seen by a planning instance. The environment
geometry, the robot geometry and state are maintained. */
class PlanningScene : private boost::noncopyable, public std::enable_shared_from_this<PlanningScene>
class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : private boost::noncopyable,
public std::enable_shared_from_this<PlanningScene>
{
public:
/** \brief construct using an existing RobotModel */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@
#include <random_numbers/random_numbers.h>
#include <Eigen/Geometry>

#undef near

namespace moveit
{
namespace core
Expand Down
4 changes: 4 additions & 0 deletions moveit_ros/benchmarks/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,13 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/BenchmarkExecutor.cpp
)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
if(WIN32)
set(EXTRA_LIB ws2_32.lib)
endif()
ament_target_dependencies(${MOVEIT_LIB_NAME}
${THIS_PACKAGE_INCLUDE_DEPENDS}
)
target_link_libraries(${MOVEIT_LIB_NAME} ${EXTRA_LIB})

add_executable(moveit_run_benchmark src/RunBenchmark.cpp)
ament_target_dependencies(moveit_run_benchmark
Expand Down
3 changes: 3 additions & 0 deletions moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,12 +49,15 @@
#include <boost/math/constants/constants.hpp>
#include <boost/filesystem.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <limits>
#ifndef _WIN32
#include <unistd.h>
#else
#include <winsock2.h>
#endif

#undef max

using namespace moveit_ros_benchmarks;

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.benchmarks.BenchmarkExecutor");
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ class ServoCalcs

const int gazebo_redundant_message_count_ = 30;

uint num_joints_;
unsigned int num_joints_;

// True -> allow drift in this dimension. In the command frame. [x, y, z, roll, pitch, yaw]
std::array<bool, 6> drift_dimensions_ = { { false, false, false, false, false, false } };
Expand Down
6 changes: 5 additions & 1 deletion moveit_ros/perception/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,11 @@ if(WITH_OPENGL)
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut)
else()
find_package(GLUT REQUIRED)
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT)
if(WIN32)
set(SYSTEM_GL_LIBRARIES GLEW::glew GLUT::GLUT)
else()
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT)
endif()
endif()
set(perception_GL_INCLUDE_DIRS "mesh_filter/include" "depth_image_octomap_updater/include")
set(SYSTEM_GL_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} ${GLUT_INCLUDE_DIR})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <stdint.h>

#include <memory>
#include <boost/bind.hpp>

namespace occupancy_map_monitor
{
Expand Down
4 changes: 4 additions & 0 deletions moveit_ros/perception/mesh_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED
src/gl_renderer.cpp
src/gl_mesh.cpp
)
include(GenerateExportHeader)
generate_export_header(${MOVEIT_LIB_NAME})
target_include_directories(${MOVEIT_LIB_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
Expand Down Expand Up @@ -40,3 +43,4 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES})
# endif()

install(DIRECTORY include/ DESTINATION include)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${MOVEIT_LIB_NAME}_export.h DESTINATION include)
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@
#include <mutex>
#include <map>

#undef near
#undef far

namespace mesh_filter
{
MOVEIT_CLASS_FORWARD(GLRenderer); // Defines GLRendererPtr, ConstPtr, WeakPtr... etc
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,15 @@
#include <moveit/mesh_filter/sensor_model.h>
#include <string>

#include "moveit_mesh_filter_export.h"

namespace mesh_filter
{
/**
* \brief Model for Disparity based devices. E.g stereo camera systems or OpenNI compatible devices
* \author Suat Gedikli <[email protected]>
*/
class StereoCameraModel : public SensorModel
class MOVEIT_MESH_FILTER_EXPORT StereoCameraModel : public SensorModel
{
public:
/**
Expand Down
Loading

0 comments on commit ad19978

Please sign in to comment.