diff --git a/moveit_ros/perception/CMakeLists.txt b/moveit_ros/perception/CMakeLists.txt index b656319b8f..27ce4ca893 100644 --- a/moveit_ros/perception/CMakeLists.txt +++ b/moveit_ros/perception/CMakeLists.txt @@ -21,8 +21,15 @@ if(WITH_OPENGL) endif() find_package(OpenGL REQUIRED) find_package(GLEW REQUIRED) - find_package(GLUT REQUIRED) + set(gl_LIBS ${gl_LIBS} ${OPENGL_LIBRARIES}) + if(APPLE) + find_package(FreeGLUT REQUIRED) + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLEW::GLEW FreeGLUT::freeglut) + else() + find_package(GLUT REQUIRED) + set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} GLUT::GLUT) + 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}) endif() diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index f637c59b63..4edc9a3758 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -120,7 +120,8 @@ bool DepthImageOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node) mesh_filter_->setShadowThreshold(shadow_threshold_); mesh_filter_->setPaddingOffset(padding_offset_); mesh_filter_->setPaddingScale(padding_scale_); - mesh_filter_->setTransformCallback(boost::bind(&DepthImageOctomapUpdater::getShapeTransform, this, _1, _2)); + mesh_filter_->setTransformCallback(boost::bind(&DepthImageOctomapUpdater::getShapeTransform, this, + boost::placeholders::_1, boost::placeholders::_2)); // init rclcpp time default value last_update_time_ = node_->now(); @@ -140,9 +141,11 @@ void DepthImageOctomapUpdater::start() pub_filtered_label_image_ = filtered_label_transport_->advertiseCamera("filtered_label", 1); - sub_depth_image_ = image_transport::create_camera_subscription( - node_.get(), image_topic_, boost::bind(&DepthImageOctomapUpdater::depthImageCallback, this, _1, _2), "raw", - custom_qos); + sub_depth_image_ = + image_transport::create_camera_subscription(node_.get(), image_topic_, + boost::bind(&DepthImageOctomapUpdater::depthImageCallback, this, + boost::placeholders::_1, boost::placeholders::_2), + "raw", custom_qos); } void DepthImageOctomapUpdater::stop() diff --git a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt index ae38c52cf0..98dbb81058 100644 --- a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt +++ b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt @@ -4,6 +4,9 @@ add_library(${MOVEIT_LIB_NAME} SHARED src/lazy_free_space_updater.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}") +if(APPLE) + target_link_libraries(${MOVEIT_LIB_NAME} OpenMP::OpenMP_CXX) +endif() ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_ros_occupancy_map_monitor diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 5f5b7f1865..6a83af3974 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -15,7 +15,8 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} Eigen3 Boost ) -target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} GLUT::GLUT ${GLEW_LIBRARIES}) + +target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) # TODO: Port to ROS2 # add_library(moveit_depth_self_filter SHARED diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index 92f01b44af..fec53a26e5 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -39,8 +39,8 @@ #include #else #include -#endif #include +#endif #include #include #include diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index fbddf61674..4007b4da4f 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -86,7 +86,8 @@ bool PointCloudOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node) tf_buffer_->setCreateTimerInterface(create_timer_interface); tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_)); shape_mask_.reset(new point_containment_filter::ShapeMask()); - shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, _1, _2)); + shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, + boost::placeholders::_1, boost::placeholders::_2)); last_update_time_ = node_->now(); return true; } @@ -104,13 +105,15 @@ void PointCloudOctomapUpdater::start() { point_cloud_filter_ = new tf2_ros::MessageFilter( *point_cloud_subscriber_, *tf_buffer_, monitor_->getMapFrame(), 5, node_); - point_cloud_filter_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_filter_->registerCallback( + boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, boost::placeholders::_1)); RCLCPP_INFO(LOGGER, "Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(), point_cloud_filter_->getTargetFramesString().c_str()); } else { - point_cloud_subscriber_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_subscriber_->registerCallback( + boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, boost::placeholders::_1)); RCLCPP_INFO(LOGGER, "Listening to '%s'", point_cloud_topic_.c_str()); } }