From 3bf49cbf91a8ac976edf4a5961a0fe808597887f Mon Sep 17 00:00:00 2001 From: unknown Date: Wed, 7 Jun 2023 11:27:59 +0200 Subject: [PATCH 1/6] [refact] Replace boost::system::create_dir to erase boost dep --- .../include/LidarSlam/PointCloudStorage.h | 4 +- slam_lib/include/LidarSlam/Utilities.h | 17 +++++ slam_lib/src/Utilities.cxx | 63 +++++++++++++++++++ 3 files changed, 81 insertions(+), 3 deletions(-) diff --git a/slam_lib/include/LidarSlam/PointCloudStorage.h b/slam_lib/include/LidarSlam/PointCloudStorage.h index 2460713c5..884aca530 100644 --- a/slam_lib/include/LidarSlam/PointCloudStorage.h +++ b/slam_lib/include/LidarSlam/PointCloudStorage.h @@ -24,8 +24,6 @@ #define PCL_NO_PRECOMPILE #endif #include -#include - #include "LidarSlam/Utilities.h" // PCL Octree compression does not compile properly on Windows with MSVC @@ -254,7 +252,7 @@ struct PCDFilePointCloud final : public PointCloudData PCDFilePointCloud(CloudTPtr const& cloud, std::string const& pcdDirPath = "point_cloud_log/") { - boost::filesystem::create_directory(pcdDirPath); + Utils::CreateDir(pcdDirPath); this->PCDFilePath = pcdDirPath + std::to_string(this->PCDFileIndex) + ".pcd"; this->PCDFileIndex++; this->SetCloud(cloud); diff --git a/slam_lib/include/LidarSlam/Utilities.h b/slam_lib/include/LidarSlam/Utilities.h index e7a021be2..829c08749 100644 --- a/slam_lib/include/LidarSlam/Utilities.h +++ b/slam_lib/include/LidarSlam/Utilities.h @@ -30,6 +30,13 @@ #include #include #include +#include + +#include +#include +#ifdef WIN32 + #include +#endif //============================================================================== // Usefull macros or typedefs @@ -177,6 +184,16 @@ void SafeAdvance(It& it, int steps, const It& stop) } } +//------------------------------------------------------------------------------ +// Check if a directory exists +bool DoesDirExist(const std::string& path); + +/*! + * @brief Create a directory + * This will also create recursively his parents folders +*/ +bool CreateDir(const std::string& path); + //============================================================================== // Geometry helpers //============================================================================== diff --git a/slam_lib/src/Utilities.cxx b/slam_lib/src/Utilities.cxx index 16d8f8134..e24f77c76 100644 --- a/slam_lib/src/Utilities.cxx +++ b/slam_lib/src/Utilities.cxx @@ -25,6 +25,69 @@ namespace LidarSlam { namespace Utils { +//============================================================================== +// Common helpers +//============================================================================== +//------------------------------------------------------------------------------ +bool DoesDirExist(const std::string& path) +{ + #ifdef WIN32 + struct _stat info; + if (_stat(path.c_str(), &info) != 0) + return false; + return (info.st_mode & _S_IFDIR) != 0; + #else + struct stat info; + if (stat(path.c_str(), &info) != 0) + return false; + return (info.st_mode & S_IFDIR) != 0; + #endif +} + +//------------------------------------------------------------------------------ +bool CreateDir(const std::string& path) +{ + #ifdef WIN32 + int ret = _mkdir(path.c_str()); + #else + mode_t mode = 0755; + int ret = mkdir(path.c_str(), mode); + #endif + if (ret == 0) + return true; + + switch (errno) + { + case ENOENT: + // Parent didn't exist, try to create it + { + int pos = path.find_last_of('/'); + if (pos == std::string::npos) + { + #ifdef WIN32 + pos = path.find_last_of('\\'); + if (pos == std::string::npos) + #endif + return false; + } + if (!CreateDir(path.substr(0, pos))) + return false; + } + // Now, try to create again + #ifdef WIN32 + return _mkdir(path.c_str()) == 0; + #else + return mkdir(path.c_str(), mode) == 0; + #endif + + case EEXIST: + return DoesDirExist(path); + + default: + return false; + } +} + //============================================================================== // Geometry helpers //============================================================================== -- GitLab From d629dfc06611933e809369c6b868d2e5cf3c80d7 Mon Sep 17 00:00:00 2001 From: unknown Date: Wed, 7 Jun 2023 11:31:09 +0200 Subject: [PATCH 2/6] [ROS][feat] ROS2 : fix Slam to work on Windows 10 Use only unaligned Eigen structure to avoid heap corruption. Fix boost and PCL dependencies. --- .../lidar_conversions/CMakeLists.txt | 19 +++++++++---------- ros2_wrapping/lidar_conversions/package.xml | 2 ++ ros2_wrapping/lidar_slam/CMakeLists.txt | 12 +++++++++++- ros2_wrapping/lidar_slam/package.xml | 4 +++- .../lidar_slam/src/ros_transform_utils.h | 3 ++- .../include/LidarSlam/ConfidenceEstimators.h | 2 +- slam_lib/include/LidarSlam/Slam.h | 2 +- slam_lib/include/LidarSlam/State.h | 2 +- 8 files changed, 30 insertions(+), 16 deletions(-) diff --git a/ros2_wrapping/lidar_conversions/CMakeLists.txt b/ros2_wrapping/lidar_conversions/CMakeLists.txt index 1d8329cfe..41cffd5c6 100644 --- a/ros2_wrapping/lidar_conversions/CMakeLists.txt +++ b/ros2_wrapping/lidar_conversions/CMakeLists.txt @@ -38,24 +38,25 @@ include_directories( # Velodyne Lidar add_executable(velodyne_conversion_node src/VelodyneToLidarNode.cxx) -#link dependencies to target -ament_target_dependencies(velodyne_conversion_node +set (conversion_dependencies rclcpp pcl_ros pcl_conversions sensor_msgs ) +#link dependencies to target +ament_target_dependencies(velodyne_conversion_node + ${conversion_dependencies} +) + # Ouster Lidar add_executable(ouster_conversion_node src/OusterToLidarNode.cxx) #link dependencies to target ament_target_dependencies(ouster_conversion_node - rclcpp - pcl_ros - pcl_conversions - sensor_msgs + ${conversion_dependencies} ) # Robosense RSLidar @@ -63,10 +64,7 @@ add_executable(robosense_conversion_node src/RobosenseToLidarNode.cxx) #link dependencies to target ament_target_dependencies(robosense_conversion_node - rclcpp - pcl_ros - pcl_conversions - sensor_msgs + ${conversion_dependencies} ) ############# @@ -76,4 +74,5 @@ ament_target_dependencies(robosense_conversion_node install(TARGETS velodyne_conversion_node ouster_conversion_node robosense_conversion_node RUNTIME DESTINATION lib/${PROJECT_NAME}) +ament_export_dependencies(${conversion_dependencies}) ament_package() \ No newline at end of file diff --git a/ros2_wrapping/lidar_conversions/package.xml b/ros2_wrapping/lidar_conversions/package.xml index 4ca635d13..97424cb62 100644 --- a/ros2_wrapping/lidar_conversions/package.xml +++ b/ros2_wrapping/lidar_conversions/package.xml @@ -30,6 +30,8 @@ pcl_conversions sensor_msgs + libpcl-common + libpcl-io rosidl_default_runtime. diff --git a/ros2_wrapping/lidar_slam/CMakeLists.txt b/ros2_wrapping/lidar_slam/CMakeLists.txt index 424c73a05..12941fd8d 100644 --- a/ros2_wrapping/lidar_slam/CMakeLists.txt +++ b/ros2_wrapping/lidar_slam/CMakeLists.txt @@ -8,6 +8,11 @@ if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE RelWithDebInfo) endif() +# Add binobj to increase address capacity on Windows +if (WIN32) + add_compile_options(/bigobj) +endif() + ################## ## Dependencies ## ################## @@ -102,7 +107,7 @@ else() message("ROS wrapping : cv_bridge was not found, camera interface cannot be used") endif() -ament_target_dependencies(lidar_slam_node +set(lidar_slam_dependencies rclcpp tf2_ros pcl_conversions @@ -114,6 +119,10 @@ ament_target_dependencies(lidar_slam_node ${optional_DEP} ) +ament_target_dependencies(lidar_slam_node + ${lidar_slam_dependencies} +) + target_link_libraries(lidar_slam_node LidarSlam "${cpp_typesupport_target}" @@ -145,4 +154,5 @@ install(DIRECTORY launch params # Installs the package.xml # Installs config (and possibly target) files for CMake so that it can be found by other packages +ament_export_dependencies(${lidar_slam_dependencies}) ament_package() \ No newline at end of file diff --git a/ros2_wrapping/lidar_slam/package.xml b/ros2_wrapping/lidar_slam/package.xml index 47a7c0b73..ff3b99d56 100644 --- a/ros2_wrapping/lidar_slam/package.xml +++ b/ros2_wrapping/lidar_slam/package.xml @@ -5,7 +5,7 @@ ROS wrapping of Kitware LiDAR SLAM algorithm. - Julia Sanchez + Arthur Bourbousson @@ -26,6 +26,8 @@ apriltag_ros cv_bridge + libpcl-common + libpcl-io message_runtime lidar_conversions gps_conversions diff --git a/ros2_wrapping/lidar_slam/src/ros_transform_utils.h b/ros2_wrapping/lidar_slam/src/ros_transform_utils.h index c5d70d3cf..257b0061c 100644 --- a/ros2_wrapping/lidar_slam/src/ros_transform_utils.h +++ b/ros2_wrapping/lidar_slam/src/ros_transform_utils.h @@ -26,6 +26,7 @@ #include #include #include +#include namespace Utils { @@ -122,7 +123,7 @@ bool Tf2LookupTransform(Eigen::Isometry3d& transform, } catch (tf2::TransformException& ex) { - PRINT_ERROR(ex.what()); + std::cerr << ex.what() << std::endl; return false; } const geometry_msgs::msg::Transform& t = tfStamped.transform; diff --git a/slam_lib/include/LidarSlam/ConfidenceEstimators.h b/slam_lib/include/LidarSlam/ConfidenceEstimators.h index 17eabab19..44e4c4b71 100644 --- a/slam_lib/include/LidarSlam/ConfidenceEstimators.h +++ b/slam_lib/include/LidarSlam/ConfidenceEstimators.h @@ -160,7 +160,7 @@ public: void SetWindowSize(unsigned int size); float GetOverlapDerivativeThreshold() const {return this->OverlapDerivativeThreshold;} - void SetOverlapDerivativeThreshold(float overlapThresh) {std::abs(this->OverlapDerivativeThreshold = overlapThresh);} + void SetOverlapDerivativeThreshold(float overlapThresh) {this->OverlapDerivativeThreshold = std::abs(overlapThresh);} float GetPositionErrorThreshold() const {return this->PositionErrorThreshold;} void SetPositionErrorThreshold(float posErrorThresh) {this->PositionErrorThreshold = posErrorThresh;} diff --git a/slam_lib/include/LidarSlam/Slam.h b/slam_lib/include/LidarSlam/Slam.h index a24e710f1..06a4d1f45 100644 --- a/slam_lib/include/LidarSlam/Slam.h +++ b/slam_lib/include/LidarSlam/Slam.h @@ -402,7 +402,7 @@ public: SetMacro(LogOnlyKeyframes, bool) GetMacro(LogOnlyKeyframes, bool) - GetMacro(LogStates, std::list) + GetMacro(LogStates, const std::list&) // Get the last states since last input frame timestamp // at a specified frequency // This will use external sensor measurements and/or poses interpolation diff --git a/slam_lib/include/LidarSlam/State.h b/slam_lib/include/LidarSlam/State.h index 9b2d0b55e..264c6f38b 100644 --- a/slam_lib/include/LidarSlam/State.h +++ b/slam_lib/include/LidarSlam/State.h @@ -40,7 +40,7 @@ struct LidarState // [s] Timestamp of data double Time = 0.; // Covariance of current pose - Eigen::Matrix6d Covariance = Utils::CreateDefaultCovariance(); + Eigen::Matrix Covariance = Utils::CreateDefaultCovariance(); // Index to link the pose graph (G2O) unsigned int Index = 0; -- GitLab From 76abe6facc812b0ec34b3f30561a600ce4c5721d Mon Sep 17 00:00:00 2001 From: "@arthur.bourbousson" Date: Tue, 13 Jun 2023 15:59:59 +0200 Subject: [PATCH 3/6] [ROS][feat] ROS2 : Put drivers on Linux only Velodyne_driver and ouster_driver package on ROS2 humble is not ported for windows and have some problems who would need some patches. Add a condition to ignore the driver packages on launch file on Windows system --- .../lidar_slam/launch/slam_ouster.py | 84 +++++++++--------- .../lidar_slam/launch/slam_velodyne.py | 85 ++++++++++--------- 2 files changed, 88 insertions(+), 81 deletions(-) diff --git a/ros2_wrapping/lidar_slam/launch/slam_ouster.py b/ros2_wrapping/lidar_slam/launch/slam_ouster.py index 6ee5990c5..57a7f37f4 100644 --- a/ros2_wrapping/lidar_slam/launch/slam_ouster.py +++ b/ros2_wrapping/lidar_slam/launch/slam_ouster.py @@ -54,45 +54,48 @@ def generate_launch_description(): ##################### ### Ouster driver ### ##################### - ouster_driver_path = get_package_share_directory("ouster_ros") - - group_ouster = GroupAction( - actions=[ - # Replay - IncludeLaunchDescription( - XMLLaunchDescriptionSource([os.path.join(ouster_driver_path, "launch", "replay.launch.xml")]), - launch_arguments={ - "timestamp_mode" : "TIME_FROM_INTERNAL_OSC", - "bag_file" : "b", - "metadata" : LaunchConfiguration("metadata_in"), - "sensor_frame" : "laser_sensor_frame", - "laser_frame" : "laser_data_frame", - "imu_frame" : "imu_data_frame", - "viz" : "False", - }.items(), - condition=IfCondition(LaunchConfiguration("replay")), - ), - # Live - IncludeLaunchDescription( - XMLLaunchDescriptionSource([os.path.join(ouster_driver_path, "launch", "sensor.launch.xml")]), - launch_arguments={ - "sensor_hostname" : LaunchConfiguration("sensor_hostname"), - "udp_dest" : LaunchConfiguration("udp_dest"), - "lidar_port" : LaunchConfiguration("lidar_port"), - "imu_port" : LaunchConfiguration("imu_port"), - "lidar_mode" : LaunchConfiguration("lidar_mode"), - "timestamp_mode" : "TIME_FROM_INTERNAL_OSC", - "metadata" : LaunchConfiguration("metadata_out"), - "sensor_frame" : "laser_sensor_frame", - "laser_frame" : "laser_data_frame", - "imu_frame" : "imu_data_frame", - "viz" : "False", - }.items(), - condition=UnlessCondition(LaunchConfiguration("replay")), - ), - ], - condition=IfCondition(LaunchConfiguration("os_driver")) - ) + + #! For now ouster packages are not ported on Windows 10 + if os.name != 'nt': + ouster_driver_path = get_package_share_directory("ouster_ros") + + group_ouster = GroupAction( + actions=[ + # Replay + IncludeLaunchDescription( + XMLLaunchDescriptionSource([os.path.join(ouster_driver_path, "launch", "replay.launch.xml")]), + launch_arguments={ + "timestamp_mode" : "TIME_FROM_INTERNAL_OSC", + "bag_file" : "b", + "metadata" : LaunchConfiguration("metadata_in"), + "sensor_frame" : "laser_sensor_frame", + "laser_frame" : "laser_data_frame", + "imu_frame" : "imu_data_frame", + "viz" : "False", + }.items(), + condition=IfCondition(LaunchConfiguration("replay")), + ), + # Live + IncludeLaunchDescription( + XMLLaunchDescriptionSource([os.path.join(ouster_driver_path, "launch", "sensor.launch.xml")]), + launch_arguments={ + "sensor_hostname" : LaunchConfiguration("sensor_hostname"), + "udp_dest" : LaunchConfiguration("udp_dest"), + "lidar_port" : LaunchConfiguration("lidar_port"), + "imu_port" : LaunchConfiguration("imu_port"), + "lidar_mode" : LaunchConfiguration("lidar_mode"), + "timestamp_mode" : "TIME_FROM_INTERNAL_OSC", + "metadata" : LaunchConfiguration("metadata_out"), + "sensor_frame" : "laser_sensor_frame", + "laser_frame" : "laser_data_frame", + "imu_frame" : "imu_data_frame", + "viz" : "False", + }.items(), + condition=UnlessCondition(LaunchConfiguration("replay")), + ), + ], + condition=IfCondition(LaunchConfiguration("os_driver")) + ) ########## ## Slam ## @@ -168,7 +171,8 @@ def generate_launch_description(): ld.add_action(rviz_node) ld.add_action(ouster_conversion_node) - ld.add_action(group_ouster) + if os.name != 'nt': + ld.add_action(group_ouster) ld.add_action(slam_outdoor_node) ld.add_action(slam_indoor_node) ld.add_action(aggregation_node) diff --git a/ros2_wrapping/lidar_slam/launch/slam_velodyne.py b/ros2_wrapping/lidar_slam/launch/slam_velodyne.py index 6b587546b..b4a613df9 100644 --- a/ros2_wrapping/lidar_slam/launch/slam_velodyne.py +++ b/ros2_wrapping/lidar_slam/launch/slam_velodyne.py @@ -51,46 +51,48 @@ def generate_launch_description(): ## Velodyne ## ############## - # Manualy override velodyne_driver_node parameters - params_velod_driver_path = os.path.join(get_package_share_directory('velodyne_driver'), 'config', 'VLP16-velodyne_driver_node-params.yaml') - with open(params_velod_driver_path, 'r') as f: - params_velod_driv = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters'] - - params_velod_driv['device_ip'] = LaunchConfiguration('device_ip') - params_velod_driv["gps_time"] = False - params_velod_driv["read_once"] = True - params_velod_driv["read_fast"] = False - params_velod_driv["repeat_delay"] = 0.0 - params_velod_driv["frame_id"] = "velodyne" - params_velod_driv["model"] = "VLP16" - params_velod_driv["rpm"] = LaunchConfiguration('rpm') - params_velod_driv["pcap"] = LaunchConfiguration('pcap') - params_velod_driv["port"] = LaunchConfiguration('port') - - # Manualy override velodyne_convert_node parameters - velodyne_pointcloud_share_path = get_package_share_directory('velodyne_pointcloud') - params_velod_pcl_path = os.path.join(velodyne_pointcloud_share_path, 'config', 'VLP16-velodyne_convert_node-params.yaml') - with open(params_velod_pcl_path, 'r') as f: - params_velod_pcl = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters'] - - params_velod_pcl['calibration'] = os.path.join(velodyne_pointcloud_share_path, 'params', 'VLP16db.yaml') - params_velod_pcl["min_range"] = 0.4 - params_velod_pcl["max_range"] = 130.0 - params_velod_pcl["organize_cloud"] = False - params_velod_pcl["target_frame"] = "" - params_velod_pcl["fixed_frame"] = "" - - velodyne_group = GroupAction( - actions=[ - # Start driver node - Node(package='velodyne_driver', executable='velodyne_driver_node', name='velodyne_driver_node', output='both', - parameters=[params_velod_driv]), - # Start convertion node - Node(package='velodyne_pointcloud', executable='velodyne_convert_node', output='both', name='velodyne_convert_node', - parameters=[params_velod_pcl],) - ], - condition = IfCondition(LaunchConfiguration("vlp16_driver")) - ) + #! For now velodyne packages are not ported on Windows 10 + if os.name != 'nt': + # Manualy override velodyne_driver_node parameters + params_velod_driver_path = os.path.join(get_package_share_directory('velodyne_driver'), 'config', 'VLP16-velodyne_driver_node-params.yaml') + with open(params_velod_driver_path, 'r') as f: + params_velod_driv = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters'] + + params_velod_driv['device_ip'] = LaunchConfiguration('device_ip') + params_velod_driv["gps_time"] = False + params_velod_driv["read_once"] = True + params_velod_driv["read_fast"] = False + params_velod_driv["repeat_delay"] = 0.0 + params_velod_driv["frame_id"] = "velodyne" + params_velod_driv["model"] = "VLP16" + params_velod_driv["rpm"] = LaunchConfiguration('rpm') + params_velod_driv["pcap"] = LaunchConfiguration('pcap') + params_velod_driv["port"] = LaunchConfiguration('port') + + # Manualy override velodyne_convert_node parameters + velodyne_pointcloud_share_path = get_package_share_directory('velodyne_pointcloud') + params_velod_pcl_path = os.path.join(velodyne_pointcloud_share_path, 'config', 'VLP16-velodyne_convert_node-params.yaml') + with open(params_velod_pcl_path, 'r') as f: + params_velod_pcl = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters'] + + params_velod_pcl['calibration'] = os.path.join(velodyne_pointcloud_share_path, 'params', 'VLP16db.yaml') + params_velod_pcl["min_range"] = 0.4 + params_velod_pcl["max_range"] = 130.0 + params_velod_pcl["organize_cloud"] = False + params_velod_pcl["target_frame"] = "" + params_velod_pcl["fixed_frame"] = "" + + velodyne_group = GroupAction( + actions=[ + # Start driver node + Node(package='velodyne_driver', executable='velodyne_driver_node', name='velodyne_driver_node', output='both', + parameters=[params_velod_driv]), + # Start convertion node + Node(package='velodyne_pointcloud', executable='velodyne_convert_node', output='both', name='velodyne_convert_node', + parameters=[params_velod_pcl],) + ], + condition = IfCondition(LaunchConfiguration("vlp16_driver")) + ) ########## ## Slam ## @@ -175,7 +177,8 @@ def generate_launch_description(): "--frame-id", "odom", "--child-frame-id", "base_link"], ) - ld.add_action(velodyne_group) + if os.name != "nt" : + ld.add_action(velodyne_group) ld.add_action(velodyne_conversion_node) ld.add_action(slam_outdoor_node) ld.add_action(slam_indoor_node) -- GitLab From bd1cb72f6521197fd2aa4352aa814ad0d8ef9b8a Mon Sep 17 00:00:00 2001 From: "@arthur.bourbousson" Date: Wed, 14 Jun 2023 14:25:16 +0200 Subject: [PATCH 4/6] [feat] Add additionnal windows dep to lidar_slam_test Add macro to use math constants --- ros2_wrapping/tests/src/LidarSlamTestNode.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ros2_wrapping/tests/src/LidarSlamTestNode.h b/ros2_wrapping/tests/src/LidarSlamTestNode.h index 0b83a82f1..a4ce59874 100644 --- a/ros2_wrapping/tests/src/LidarSlamTestNode.h +++ b/ros2_wrapping/tests/src/LidarSlamTestNode.h @@ -18,6 +18,9 @@ #pragma once +#define _USE_MATH_DEFINES +#include + #include #include #include -- GitLab From 459c4f57401c5d5bf06c46d836e44c009aaecffa Mon Sep 17 00:00:00 2001 From: "@arthur.bourbousson" Date: Wed, 14 Jun 2023 16:33:02 +0200 Subject: [PATCH 5/6] [ROS][doc] Update documentation to use ROS2 on Windows 10 Add instructions to use ROS2 wrapping of the SLAM on Windows 10 --- README.md | 55 +++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 55 insertions(+) diff --git a/README.md b/README.md index 9c26b2a04..c8626853b 100644 --- a/README.md +++ b/README.md @@ -16,6 +16,9 @@ - [Dependencies](#dependencies-2) - [Installation](#installation-2) - [Usage](#usage-1) +- [ROS2 wrapping on Windows 10](##ros2-wrapping-on-windows-10) + - [Dependencies](#install-dependencies) + - [Installation](#install-slam-package) - [ParaView wrapping](#paraview-wrapping) - [Dependencies](#dependencies-3) - [Installation](#installation-3) @@ -269,6 +272,7 @@ Example : cmake --build . -j # Build Slam ROS package cd ../ros2_ws + call path\to\ros2_humble\local_setup.bat colcon build --base-paths ./slam/ros2_wrapping --cmake-args -DCMAKE_BUILD_TYPE=Release -DSUPERBUILD_INSTALL_DIR=absolute/path/to/superbuild/install ``` @@ -288,6 +292,57 @@ ros2 launch lidar_slam slam_ouster.launch replay:=false gps:=true # if GPS/SLA See [ros2_wrapping/lidar_slam/README.md](ros2_wrapping/lidar_slam/README.md) for more details. +## ROS2 wrapping on Windows 10 + +**WARNING** : ROS2 is supported on Windows 10 but many packages are not ported and the installation can be tricky. + +**NOTE** : Always use administrator x64_x86 Cross Tools Command Prompt for VS 2019 + +### Install dependencies + +#### Install ROS2 and slam dependencies +Install ROS2 humble version by following [official instructions](https://docs.ros.org/en/humble/Installation/Windows-Install-Binary.html) + +Install slam dependencies with the [SLAM superbuild](https://gitlab.kitware.com/keu-computervision/slam-superbuild) on Release mode. You can use MSVC or Ninja as generator. +The instructions can be found in the section [above](#with-superbuild). + +To use dependencies installed on the superbuild, you need to set the PATH env +``` +set PATH=path\to\Slam_SB\install\bin;%PATH% +``` + +#### Install pcl-conversions +Create a workspace for pcl-conversions package +Be sure to have PCL in the PATH env + +```bash +mkdir ws_pcl/src && cd ws_pcl\src +git clone https://github.com/ros-perception/perception_pcl.git -b ros2 +git clone https://github.com/ros-perception/pcl_msgs.git -b ros2 +cd .. +call path\to\ros2_humble\local_setup.bat +colcon build --merge-install --packages-up-to pcl_conversions +``` +To use pcl-conversions package, you need to source your command prompt +```bash +call path\to\ws_pcl\install\setup.bat +``` + +### Install SLAM package +Be sure to have the superbuild in the PATH and pcl_conversions sourced +```bash +mkdir ws_ros2 +dir ws_ros2 +git clone https://gitlab.kitware.com/keu-computervision/slam -b feat/ROS2 +call path\to\ros2_humble\local_setup.bat +colcon build --base-paths=slam\ros2_wrapping --merge-install --cmake-args -DCMAKE_BUILD_TYPE=Release -DENABLE_OpenCV=OFF +``` +source the SLAM +``` +call install/setup.bat +``` +The SLAM is ready to use. Please make sure that the superbuild bin path is in the PATH var and pcl_conversions is sourced. + ## ParaView wrapping The *LidarSlamPlugin* Paraview wrapping has been tested on Linux, Windows and OS X. -- GitLab From 6579125facacc5c09ce25885a19f2f0035d87b52 Mon Sep 17 00:00:00 2001 From: "@arthur.bourbousson" Date: Thu, 15 Jun 2023 12:00:46 +0200 Subject: [PATCH 6/6] [fix][build] Fix SLAM Superbuild on Windows Add /bigobj compilation option for dependencies and debug mode. --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index dc104fdc8..c13f02694 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -36,6 +36,7 @@ list(APPEND CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR} # MSVC enforce MT if(WIN32 AND MSVC) set(CMAKE_MSVC_RUNTIME_LIBRARY "MultiThreadedDLL") + add_compile_options(/bigobj) endif() # Boost do not use STATIC libs (Superbuild like), coherent with BUILD_SHARED_LIBS ON -- GitLab