diff --git a/CMakeLists.txt b/CMakeLists.txt index 0e9a142..c81421a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,7 +4,12 @@ project(multimotionfusion) set(CMAKE_CXX_STANDARD 17) # Warnings / Errors -add_compile_options(-Wall -Werror -Wno-write-strings -Wno-deprecated-declarations) +add_compile_options( + $<$:-Wall> + $<$:-Werror> + $<$:-Wno-write-strings> + $<$:-Wno-deprecated-declarations> +) # Don't follow symlinks when FILE GLOB_RECURSE (and don't warn) cmake_policy(SET CMP0009 NEW) diff --git a/Core/CMakeLists.txt b/Core/CMakeLists.txt index bb06f11..aff44b4 100644 --- a/Core/CMakeLists.txt +++ b/Core/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.0.2) -project(multimotionfusion) +project(multimotionfusion LANGUAGES CXX CUDA) message(STATUS "Evaluating Core/CMAKE") @@ -9,7 +9,6 @@ set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}") include(GNUInstallDirs) ## External packages -find_package(CUDA REQUIRED) find_package(SuiteSparse REQUIRED) find_package(OpenCV REQUIRED) find_package(OpenMP) @@ -65,7 +64,7 @@ message(STATUS "MULTIMOTIONFUSION_SHADER_DIR: ${MULTIMOTIONFUSION_SHADER_DIR}") ## Includes include_directories(${Pangolin_INCLUDE_DIRS}) -include_directories(${CUDA_INCLUDE_DIRS}) +include_directories(${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}) include_directories(${SUITESPARSE_INCLUDE_DIRS}) include_directories(${PCL_INCLUDE_DIRS}) include_directories(${OpenCV_INCLUDE_DIRS}) @@ -98,8 +97,6 @@ endif(CMAKE_BUILD_TYPE MATCHES Debug) # disable to use standard 'glTransformFeedbackVaryings' in palce of 'glTransformFeedbackVaryingsNV' add_definitions(-DNVIDIA_VARYINGS) -CUDA_COMPILE(cuda_objs ${cuda}) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -msse -msse2 -msse3 -DSHADER_DIR=${MULTIMOTIONFUSION_SHADER_DIR}") if(CMAKE_BUILD_TYPE MATCHES Debug) @@ -117,7 +114,6 @@ add_library(${PROJECT_NAME} SHARED ${utils_srcs} ${shader_srcs} ${cuda} - ${cuda_objs} ${containers} ${segmentation} ) @@ -126,7 +122,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${ZLIB_INCLUDE_DIR} ${Pangolin_INCLUDE_DIRS} - ${CUDA_INCLUDE_DIRS} + ${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES} ${OPENNI2_INCLUDE_DIR} ${OpenCV_INCLUDE_DIRS} ${BOOST_INCLUDE_DIRS} @@ -142,6 +138,9 @@ target_link_libraries(${PROJECT_NAME} super_point_inference ) +target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_11) +set_target_properties(${PROJECT_NAME} PROPERTIES CUDA_SEPARABLE_COMPILATION ON) + add_library(ransac STATIC "Utils/RigidRANSAC.cpp") target_link_libraries(ransac Eigen3::Eigen) diff --git a/GUI/CMakeLists.txt b/GUI/CMakeLists.txt index 39ae3e7..d83793e 100644 --- a/GUI/CMakeLists.txt +++ b/GUI/CMakeLists.txt @@ -1,22 +1,28 @@ cmake_minimum_required(VERSION 3.5) -project(multimotionfusion-gui) +project(multimotionfusion-gui LANGUAGES CXX CUDA) set(CMAKE_CXX_STANDARD 17) message(STATUS "Evaluating GUI/CMAKE") +if($ENV{ROS_VERSION}) +set(HASROS ON) if($ENV{ROS_VERSION} EQUAL 1) set(HASROS1 ON) + add_compile_options(-DROS1) +elseif($ENV{ROS_VERSION} EQUAL 2) + set(HASROS2 ON) + add_compile_options(-DROS2) +endif() endif() option(ROSBAG "rosbag reader" ${HASROS1}) -option(ROSNODE "read images live as ROS node" ${HASROS1}) +option(ROSNODE "read images live as ROS node" ${HASROS}) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}") find_package(ZLIB REQUIRED) -find_package(CUDA REQUIRED) find_package(OpenNI2 REQUIRED) find_package(OpenCV REQUIRED ) find_package(Boost REQUIRED filesystem) @@ -32,10 +38,14 @@ if(ROSBAG) endif() if(ROSNODE) - find_package(roscpp REQUIRED) + if(HASROS1) + find_package(roscpp REQUIRED) + find_package(eigen_conversions REQUIRED) + add_compile_options(-DROSUI -DROSSTATE) + endif() + add_compile_options(-DROSREADER) find_package(image_transport REQUIRED) find_package(tf2_ros REQUIRED) - find_package(eigen_conversions REQUIRED) find_package(cob_srvs REQUIRED) endif() @@ -46,7 +56,7 @@ if(ROSBAG OR ROSNODE) endif() include_directories(${ZLIB_INCLUDE_DIR}) -include_directories(${CUDA_INCLUDE_DIRS}) +include_directories(${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}) include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../Core) include_directories(${OPENNI2_INCLUDE_DIR}) include_directories(${Pangolin_INCLUDE_DIRS}) @@ -55,7 +65,7 @@ include_directories(${OpenCV_INCLUDE_DIRS}) message(STATUS "Include-directories: ") message(STATUS "ZLIB_INCLUDE_DIR: ${ZLIB_INCLUDE_DIR}") -message(STATUS "CUDA_INCLUDE_DIRS: ${CUDA_INCLUDE_DIRS}") +message(STATUS "CUDA_INCLUDE_DIRS: ${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}") message(STATUS "OPENNI2_INCLUDE_DIR: ${OPENNI2_INCLUDE_DIR}") message(STATUS "CMAKE_CURRENT_SOURCE_DIR/../Core: ${${CMAKE_CURRENT_SOURCE_DIR}/../Core}") @@ -101,7 +111,7 @@ target_include_directories(MultiMotionFusionTools PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${ZLIB_INCLUDE_DIR} ${Pangolin_INCLUDE_DIRS} - ${CUDA_INCLUDE_DIRS} + ${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES} ${OPENNI2_INCLUDE_DIR} ${OpenCV_INCLUDE_DIRS} ${BOOST_INCLUDE_DIRS} @@ -138,6 +148,12 @@ if(ROSNODE) ${eigen_conversions_LIBRARIES} ${cob_srvs_LIBRARIES} ) +if(HASROS2) + target_link_libraries(MultiMotionFusionTools + image_geometry::image_geometry + image_transport::image_transport + ) +endif() # to find "gSLICr.h" and "super_point_inference.hpp" target_link_libraries(MultiMotionFusionTools gSLICr_lib super_point_inference) add_definitions(-DROSNODE) @@ -154,6 +170,12 @@ if(ROSBAG OR ROSNODE) ${tf2_eigen_LIBRARIES} ${image_geometry_LIBRARIES} ) +if(HASROS2) + target_link_libraries(MultiMotionFusionTools + image_geometry::image_geometry + cv_bridge::cv_bridge + ) +endif() add_definitions(-DROSCOMMON) endif() diff --git a/GUI/MainController.cpp b/GUI/MainController.cpp index daf8d5e..b74ecfd 100644 --- a/GUI/MainController.cpp +++ b/GUI/MainController.cpp @@ -24,8 +24,10 @@ #ifdef ROSBAG #include "Tools/RosBagReader.hpp" #endif -#ifdef ROSNODE +#ifdef ROSREADER #include "Tools/RosNodeReader.hpp" +#endif +#ifdef ROSSTATE #include "Tools/RosStatePublisher.hpp" #endif @@ -244,16 +246,53 @@ MainController::MainController(int argc, char* argv[]) #ifdef ROSNODE if (Parse::get().arg(argc, argv, "-ros", empty) > 0) { // instantiate MultiMotionFusion node +#ifdef ROS1 ros::init(argc, argv, "MMF"); + executor = std::make_unique(1); + executor->start(); +#elif defined(ROS2) + const std::vector args_non_ros = rclcpp::init_and_remove_ros_arguments(argc, argv); + // reset argv without the parsed ROS args + for (int i = 0; i < argc; i++) { + memset(argv[i], 0, strlen(argv[i])); + } + argc = args_non_ros.size(); + for (size_t i=0; i(rclcpp::ExecutorOptions{}, 1); + spinner = std::thread([this](){ executor->spin(); }); +#endif +#ifdef ROSREADER // read RGB-D data if (!logReader) { - logReader = std::make_unique(15, Parse::get().arg(argc, argv, "-f", empty) > -1, target_dim); - logReaderReady = true; + try { + logReader = std::make_unique(15, Parse::get().arg(argc, argv, "-f", empty) > -1, target_dim); + logReaderReady = true; + } catch (const std::runtime_error& e) { + std::cerr << "cannot create ROS RGB-D reader: " << e.what() << std::endl; + logReader = nullptr; + logReaderReady = false; + } } +#endif +#ifdef ROSSTATE // publish segmentation and point clouds // TODO: get camera frame from input images state_publisher = std::make_unique("rgb_camera_link"); +#endif +#ifdef ROSUI ui_control = std::make_unique(&gui, &mmf); +#endif +#if defined(ROS2) + // add nodes to executor +#ifdef ROSREADER + if (logReader) { + executor->add_node(dynamic_cast(logReader.get())->n); + } +#endif +#endif } #endif @@ -403,6 +442,14 @@ MainController::MainController(int argc, char* argv[]) } MainController::~MainController() { +#ifdef ROSNODE +#ifdef ROS1 + executor->stop(); +#elif defined(ROS2) + executor->cancel(); + spinner.join(); +#endif +#endif if (mmf) { delete mmf; } @@ -455,7 +502,7 @@ void MainController::launch() { cudaCheckError(); } -#ifdef ROSNODE +#ifdef ROSSTATE if (state_publisher) { state_publisher->reset(); } @@ -481,7 +528,7 @@ void MainController::launch() { // gui->addModel(model->getID(), model->getConfidenceThreshold());} //); -#ifdef ROSNODE +#ifdef ROSSTATE if (state_publisher) { MultiMotionFusion::StatusMessageHandler send_status_message = std::bind(&RosStatePublisher::send_status_message, state_publisher.get(), std::placeholders::_1); mmf->setStatusMessageHandler(send_status_message); @@ -649,7 +696,7 @@ void MainController::run() { gui->saveColorImage(viewPath); } -#ifdef ROSNODE +#ifdef ROSSTATE if (state_publisher) { const int64_t time = logReader->getFrameData().timestamp; state_publisher->pub_segmentation(mmf->getTextures()[GPUTexture::MASK_COLOR]->downloadTexture(), time); diff --git a/GUI/MainController.h b/GUI/MainController.h index 5425693..d200448 100644 --- a/GUI/MainController.h +++ b/GUI/MainController.h @@ -25,10 +25,16 @@ #include "Tools/GroundTruthOdometry.h" #include "Tools/LogReader.h" -#ifdef ROSNODE +#ifdef ROSSTATE #include "Tools/RosStatePublisher.hpp" +#endif +#ifdef ROSUI #include "Tools/RosInterface.hpp" #endif +#if defined(ROS2) +#include +#include +#endif class MainController { public: @@ -66,11 +72,22 @@ class MainController { bool exportModels; bool restore; -#ifdef ROSNODE +#ifdef ROSSTATE std::unique_ptr state_publisher; +#endif +#ifdef ROSUI std::unique_ptr ui_control; #endif +#ifdef ROSNODE +#ifdef ROS1 + std::unique_ptr executor; +#elif defined(ROS2) + std::unique_ptr executor; + std::thread spinner; +#endif +#endif + float confGlobalInit, confObjectInit, icpErrThresh, covThresh, photoThresh, fernThresh; int timeDelta, icpCountThresh, start, end, preallocatedModelsCount; diff --git a/GUI/Tools/RosInterface.cpp b/GUI/Tools/RosInterface.cpp index ee5b096..8feaf66 100644 --- a/GUI/Tools/RosInterface.cpp +++ b/GUI/Tools/RosInterface.cpp @@ -1,4 +1,4 @@ -#ifdef ROSNODE +#ifdef ROSUI #include "RosInterface.hpp" diff --git a/GUI/Tools/RosNodeReader.cpp b/GUI/Tools/RosNodeReader.cpp index faf5458..b21c4fa 100644 --- a/GUI/Tools/RosNodeReader.cpp +++ b/GUI/Tools/RosNodeReader.cpp @@ -1,9 +1,22 @@ -#ifdef ROSNODE +#ifdef ROSREADER #include "RosNodeReader.hpp" -#include #include -#include + +#if defined(ROS1) + #include + #include + #include + using namespace sensor_msgs; + using namespace std_msgs; +#elif defined(ROS2) + #include + #include + #include + #include + using namespace sensor_msgs::msg; + using namespace std_msgs::msg; +#endif RosNodeReader::RosNodeReader(const uint32_t synchroniser_queue_size, @@ -12,21 +25,39 @@ RosNodeReader::RosNodeReader(const uint32_t synchroniser_queue_size, LogReader(std::string(), flipColors), frame_gt_camera(frame_gt_camera) { +#if defined(ROS1) n = std::make_unique(); it = std::make_unique(*n); +#elif defined(ROS2) + n = std::make_shared("MMF"); + const std::string transport = n->declare_parameter("image_transport", "raw"); +#endif tf_listener = std::make_unique(tf_buffer); - sub_colour.subscribe(*it, ros::names::resolve("colour"), 1); - sub_depth.subscribe(*it, ros::names::resolve("depth"), 1); +#if defined(ROS1) + sub_colour.subscribe(*it, resolve("colour"), 1); + sub_depth.subscribe(*it, resolve("depth"), 1); +#elif defined(ROS2) + sub_colour.subscribe(n.get(), resolve("colour"), transport); + sub_depth.subscribe(n.get(), resolve("depth"), transport); +#endif sync = std::make_unique>(ApproximateTimePolicy(synchroniser_queue_size)); sync->connectInput(sub_colour, sub_depth); sync->registerCallback(&RosNodeReader::on_rgbd, this); // wait for single CameraInfo message to get intrinsics - std::cout << "waiting for 'sensor_msgs/CameraInfo' message on '" + ros::names::resolve("camera_info") + "'" << std::endl; - sensor_msgs::CameraInfo::ConstPtr ci = ros::topic::waitForMessage("camera_info", *n); + std::cout << "waiting for 'sensor_msgs/CameraInfo' message on '" + resolve("camera_info") + "'" << std::endl; + +#if defined(ROS1) + CameraInfo::ConstPtr ci = ros::topic::waitForMessage("camera_info", *n); +#elif defined(ROS2) + CameraInfo::Ptr ci = std::make_shared(); + if(!rclcpp::wait_for_message(*ci, n, "camera_info")) { + throw std::runtime_error("error while waiting for message"); + } +#endif image_crop_target = ImageCropTarget(ci, target_dimensions); @@ -35,19 +66,16 @@ RosNodeReader::RosNodeReader(const uint32_t synchroniser_queue_size, numPixels = width * height; ref_pose.matrix().array() = 0; - - spinner = std::make_unique(1); - spinner->start(); } -RosNodeReader::~RosNodeReader() { - spinner->stop(); -} - -void RosNodeReader::on_rgbd(const sensor_msgs::Image::ConstPtr& msg_colour, const sensor_msgs::Image::ConstPtr& msg_depth) { +void RosNodeReader::on_rgbd(const Image::ConstPtr& msg_colour, const Image::ConstPtr& msg_depth) { mutex.lock(); - const std_msgs::Header hdr_colour = msg_colour->header; + const Header hdr_colour = msg_colour->header; +#if defined(ROS1) data.timestamp = int64_t(hdr_colour.stamp.toNSec()); +#elif defined(ROS2) + data.timestamp = int64_t(hdr_colour.stamp.sec * 1e9 + hdr_colour.stamp.nanosec); +#endif data.rgb = cv_bridge::toCvCopy(msg_colour, "rgb8")->image; data.depth = cv_bridge::toCvCopy(msg_depth)->image; @@ -105,8 +133,12 @@ FrameData RosNodeReader::getFrameData() { Eigen::Matrix4f RosNodeReader::getIncrementalTransformation(uint64_t timestamp) { // camera pose at requested time with respect to root frame +#if defined(ROS1) ros::Time time; time.fromNSec(timestamp); +#elif defined(ROS2) + tf2::TimePoint time{std::chrono::nanoseconds(timestamp)}; +#endif Eigen::Isometry3d pose; try { pose = tf2::transformToEigen(tf_buffer.lookupTransform(frame_gt_root, frame_gt_camera, time)); @@ -124,4 +156,12 @@ Eigen::Matrix4f RosNodeReader::getIncrementalTransformation(uint64_t timestamp) return (ref_pose.inverse() * pose).matrix().cast(); } +std::string RosNodeReader::resolve(const std::string &topic) { +#if defined(ROS1) + return ros::names::resolve(topic); +#elif defined(ROS2) + return this->n->get_node_base_interface()->resolve_topic_or_service_name(topic, false); +#endif +} + #endif diff --git a/GUI/Tools/RosNodeReader.hpp b/GUI/Tools/RosNodeReader.hpp index 4776a70..9716436 100644 --- a/GUI/Tools/RosNodeReader.hpp +++ b/GUI/Tools/RosNodeReader.hpp @@ -2,15 +2,24 @@ #pragma once #include "LogReader.h" -#include -#include -#include #include #include "ros_common.hpp" #include #include #include +#if defined(ROS1) + #include + #include + using namespace sensor_msgs; + #include +#elif defined(ROS2) + #include + #include + using namespace sensor_msgs::msg; + #include +#endif + class RosNodeReader : public LogReader, public GroundTruthOdometryInterface { public: @@ -18,9 +27,7 @@ class RosNodeReader : public LogReader, public GroundTruthOdometryInterface { const bool flipColors = false, const cv::Size &target_dimensions = {}, const std::string frame_gt_camera = {}); - ~RosNodeReader(); - - void on_rgbd(const sensor_msgs::ImageConstPtr& msg_colour, const sensor_msgs::ImageConstPtr& msg_depth); + void on_rgbd(const Image::ConstPtr& msg_colour, const Image::ConstPtr& msg_depth); void getNext() override; @@ -42,13 +49,18 @@ class RosNodeReader : public LogReader, public GroundTruthOdometryInterface { Eigen::Matrix4f getIncrementalTransformation(uint64_t timestamp) override; +#if defined(ROS2) + rclcpp::Node::SharedPtr n; +#endif + private: - typedef message_filters::sync_policies::ApproximateTime ApproximateTimePolicy; + typedef message_filters::sync_policies::ApproximateTime ApproximateTimePolicy; // node +#if defined(ROS1) std::unique_ptr n; +#endif std::unique_ptr it; - std::unique_ptr spinner; // ground truth camera poses in root frame std::string frame_gt_root; @@ -67,6 +79,8 @@ class RosNodeReader : public LogReader, public GroundTruthOdometryInterface { std::mutex mutex; FrameData data; + + std::string resolve(const std::string &topic); }; #endif diff --git a/GUI/Tools/RosStatePublisher.cpp b/GUI/Tools/RosStatePublisher.cpp index e0276fe..cf4fb69 100644 --- a/GUI/Tools/RosStatePublisher.cpp +++ b/GUI/Tools/RosStatePublisher.cpp @@ -1,4 +1,4 @@ -#ifdef ROSNODE +#ifdef ROSSTATE #include "RosStatePublisher.hpp" #include diff --git a/GUI/Tools/ros_common.cpp b/GUI/Tools/ros_common.cpp index 8ceb3c4..3bdb89a 100644 --- a/GUI/Tools/ros_common.cpp +++ b/GUI/Tools/ros_common.cpp @@ -4,6 +4,7 @@ #include #include #include +#include static std::tuple get_crop_roi(const cv::Size &source_dimensions, const cv::Size &target_dimensions) { @@ -43,7 +44,7 @@ get_crop_roi(const cv::Size &source_dimensions, const cv::Size &target_dimension return {crop_roi, scale}; } -ImageCropTarget::ImageCropTarget(const sensor_msgs::CameraInfo::ConstPtr &camera_info, +ImageCropTarget::ImageCropTarget(const CameraInfo::ConstPtr &camera_info, const cv::Size &target_dimensions) : target_dimensions(target_dimensions) { @@ -57,8 +58,13 @@ ImageCropTarget::ImageCropTarget(const sensor_msgs::CameraInfo::ConstPtr &camera // source intrinsics const cv::Size source_dimensions(camera_info->width, camera_info->height); // 'P' row-major 3x4 projection matrix: (fx, 0, cx, Tx, 0, fy, cy, Ty, 0, 0, 1, 0) +#if defined(ROS1) const Eigen::Vector2d src_f = {camera_info->P[0], camera_info->P[5]}; // focal length const Eigen::Vector2d src_c = {camera_info->P[2], camera_info->P[6]}; // centre +#elif defined(ROS2) + const Eigen::Vector2d src_f = {camera_info->p[0], camera_info->p[5]}; // focal length + const Eigen::Vector2d src_c = {camera_info->p[2], camera_info->p[6]}; // centre +#endif // source field-of-view (FoV) const Eigen::Vector2d src_d = {camera_info->width, camera_info->height}; // dimension diff --git a/GUI/Tools/ros_common.hpp b/GUI/Tools/ros_common.hpp index d049fe2..b8b2273 100644 --- a/GUI/Tools/ros_common.hpp +++ b/GUI/Tools/ros_common.hpp @@ -3,15 +3,21 @@ #pragma once #include -#include #include #include +#if defined(ROS1) + #include + using namespace sensor_msgs; +#elif defined(ROS2) + #include + using namespace sensor_msgs::msg; +#endif class ImageCropTarget { public: ImageCropTarget() = default; - ImageCropTarget(const sensor_msgs::CameraInfo::ConstPtr &camera_info, const cv::Size &target_dimensions); + ImageCropTarget(const CameraInfo::ConstPtr &camera_info, const cv::Size &target_dimensions); void map_target(FrameData &data); diff --git a/README.md b/README.md index 1262c4a..b606942 100644 --- a/README.md +++ b/README.md @@ -10,7 +10,10 @@ MultiMotionFusion implements an online tracking and modelling approach for multi - arXiv: https://doi.org/10.48550/arXiv.2204.11923 - RA-L: https://doi.org/10.1109/LRA.2022.3200177 - video: https://www.youtube.com/watch?v=b8pov4DKLsY -- example data: https://conferences.inf.ed.ac.uk/MultiMotionFusion +- example data: + - https://conferences.inf.ed.ac.uk/MultiMotionFusion + - https://github.com/christian-rauch/MultiMotionFusion-data + - https://gitlab.com/christian-rauch/MultiMotionFusion-data This project is based on [Co-Fusion](https://github.com/martinruenz/co-fusion) by Martin Rünz et al. @@ -31,7 +34,7 @@ If you use this work, please cite our paper: ## Quick Start -MultiMotionFusion is built as a colcon workspace to simplify dependency management. MultiMotionFusion needs a Nvidia GPU that supports CUDA 11. The instructions are for a fresh installation of Ubuntu 20.04. +MultiMotionFusion is built as a colcon workspace to simplify dependency management. MultiMotionFusion needs a Nvidia GPU that supports CUDA 11. The instructions are for a fresh installation of Ubuntu 20.04 or 22.04. 1. Install system dependencies (CUDA, ROS, vcstool, rosdep, colcon) using [`setup.sh`](doc/setup.sh). If any of these system dependencies are already installed, skip this step and install the remaining dependencies manually. ```sh @@ -63,6 +66,7 @@ MultiMotionFusion is built as a colcon workspace to simplify dependency manageme The following packages have to be installed manually: - [CUDA](https://developer.nvidia.com/cuda-toolkit) and [cuDNN](https://developer.nvidia.com/cudnn) for dense ICP and sparse keypoint prediction, [installation instructions](https://developer.nvidia.com/cuda-downloads?target_os=Linux&target_arch=x86_64&Distribution=Ubuntu&target_version=20.04&target_type=deb_network) - [ROS 1](https://www.ros.org/blog/getting-started/) (optionally) to read example data and live RGB-D feed from camera, [installation instructions](http://wiki.ros.org/noetic/Installation/Ubuntu) +- [ROS](https://www.ros.org/blog/getting-started/) (optionally) to read example data and live RGB-D feed from camera, [ROS 1](http://wiki.ros.org/noetic/Installation/Ubuntu) (Ubuntu 20.04) or [ROS 2](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) (Ubuntu 22.04) - [vcstool](http://wiki.ros.org/vcstool) to download source repositories - [rosdep](http://wiki.ros.org/rosdep) to automatically resolve binary dependencies - [colcon](https://colcon.readthedocs.io) to build the workspace, [installation instructions](https://colcon.readthedocs.io/en/released/user/installation.html) @@ -110,22 +114,32 @@ The bag files used in the paper are available at https://conferences.inf.ed.ac.u The paper uses the `filtered` depth images. These images have depth observations from the robot links removed using the [`realtime_urdf_filter`](https://github.com/blodow/realtime_urdf_filter) package. -Enable simulation time via `rosparam set use_sim_time true` and play the bags via `rosbag play --clock $BAG` to communicate the log time via the `/clock` topic. +On ROS 1, enable simulation time via `rosparam set use_sim_time true` and play the bags via `rosbag play --clock $FILE.bag` to communicate the log time via the `/clock` topic. -#### Run as ROS node -Executing with parameter `-ros` will register the process as ROS node and subscribe to colour and depth image topics from an RGB-D camera or ROS bag file. This supports the usual ROS remapping arguments. For a [Azure Kinect DK](https://github.com/microsoft/Azure_Kinect_ROS_Driver), you have to provide the following remapping arguments: +On ROS 2, first convert the bag files via the [`rosbags`](https://gitlab.com/ternaris/rosbags) tool (`pip install rosbags` and `rosbags-convert $FILE.bag`) and then play them back via `ros2 bag play --clock 100 $FILE`. + +#### Run as ROS node (ROS 1 and 2) +Executing with parameter `-ros` will register the process as ROS node and subscribe to colour and depth image topics from an RGB-D camera or ROS bag file. This supports the usual ROS 1 and 2 remapping arguments. For a [Azure Kinect DK](https://github.com/microsoft/Azure_Kinect_ROS_Driver), you have to provide the following remapping arguments: ```sh -MultiMotionFusion -run -dim 640x480 \ - -ros \ +# ROS 1 +MultiMotionFusion -run -dim 640x480 -ros \ colour:=/rgb/image_raw \ depth:=/depth_to_rgb/image_raw/filtered \ camera_info:=/rgb/camera_info \ _image_transport:=compressed +# ROS 2 +MultiMotionFusion -run -dim 640x480 -ros \ + --ros-args \ + -r colour:=/rgb/image_raw \ + -r depth:=/depth_to_rgb/image_raw/filtered \ + -r camera_info:=/rgb/camera_info \ + -p image_transport:=compressed ``` This will read images in real-time as they are published by the RGB-D driver or ROS bag. The node will wait for the first `sensor_msgs/CameraInfo` message on the `camera_info` topic to initialise the image dimensions and show the GUI. For convenience, create a script that sets the subset of input parameters and accepts additional parameters: ```sh +# ROS 1 cat < mmf_ros.sh #!/usr/bin/env bash MultiMotionFusion -run -dim 640x480 -ros \ @@ -135,11 +149,22 @@ MultiMotionFusion -run -dim 640x480 -ros \ _image_transport:=compressed \ \$@ EOF +# ROS 2 +cat < mmf_ros.sh +#!/usr/bin/env bash +MultiMotionFusion -run -dim 640x480 -ros \ + \$@ \ + --ros-args \ + -r colour:=/rgb/image_raw \ + -r depth:=/depth_to_rgb/image_raw/filtered \ + -r camera_info:=/rgb/camera_info \ + -p image_transport:=compressed +EOF chmod +x mmf_ros.sh ``` This script will then always run `MultiMotionFusion` as ROS node and accept additional parameters: `./mmf_ros.sh ... `. -#### Read from ROS bag +#### Read from ROS bag (ROS 1) For a deterministic behaviour, you can also read directly frame-by-frame from a ROS bag file by providing its path to the `-l` parameter and setting the topic names: ```sh MultiMotionFusion -run -dim 640x480 \ diff --git a/package.xml b/package.xml index e95165a..cd6b39f 100644 --- a/package.xml +++ b/package.xml @@ -58,6 +58,7 @@ tf2_eigen tf2_ros image_transport + compressed_image_transport cv_bridge image_geometry super_point_inference