Closed askokostic closed 3 years ago
I tried with a minimal Dockerfile (from ros:foxy) with ros-foxy-desktop and ros-foxy-libg2o (had to update rtabmap library to find that g2o on foxy), gtsam binaries (like in your dockerfile), libpointmatcher from source. Using gdb:
~/ros2_ws/install/rtabmap_ros/lib/rtabmap_ros# gdb ex run --args rtabmap
GNU gdb (Ubuntu 9.2-0ubuntu1~20.04) 9.2
Copyright (C) 2020 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<http://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
<http://www.gnu.org/software/gdb/documentation/>.
For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from rtabmap...
(No debugging symbols found in rtabmap)
(gdb) run
Starting program: /root/ros2_ws/install/rtabmap_ros/lib/rtabmap_ros/rtabmap
warning: Error disabling address space randomization: Operation not permitted
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
double free or corruption (out)
Program received signal SIGABRT, Aborted.
__GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
50 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
(gdb) bt
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1 0x00007fa561e23859 in __GI_abort () at abort.c:79
#2 0x00007fa561e8e3ee in __libc_message (action=action@entry=do_abort, fmt=fmt@entry=0x7fa561fb8285 "%s\n") at ../sysdeps/posix/libc_fatal.c:155
#3 0x00007fa561e9647c in malloc_printerr (str=str@entry=0x7fa561fba670 "double free or corruption (out)") at malloc.c:5347
#4 0x00007fa561e98120 in _int_free (av=0x7fa561fe9b80 <main_arena>, p=0x5587f111efb0, have_lock=<optimized out>) at malloc.c:4314
#5 0x00007fa55ee968e1 in g2o::EdgeProjectP2MC_Intrinsics::~EdgeProjectP2MC_Intrinsics() () at /opt/ros/foxy/lib/libg2o_types_sba.so
#6 0x00007fa55965ec84 in g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) ()
at /opt/ros/foxy/lib/libg2o_core.so
#7 0x00007fa55ee8fb47 in () at /opt/ros/foxy/lib/libg2o_types_sba.so
#8 0x00007fa56ae23b8a in () at /lib64/ld-linux-x86-64.so.2
#9 0x00007fa56ae23c91 in () at /lib64/ld-linux-x86-64.so.2
#10 0x00007fa56ae1313a in () at /lib64/ld-linux-x86-64.so.2
#11 0x0000000000000001 in ()
#12 0x00007fffeca30665 in ()
#13 0x0000000000000000 in ()
(gdb)
Looks like it is crashing in /opt/ros/foxy/lib/libg2o_types_sba.so
. I'll try to uninstall those g2o binaries and build an older g2o version.
Installing older g2o version (I did go down to 20170730_git version) does the same error. I noticed that without GTSAM dependency, it was working. I reinstalled latest g2o binaries, then installed GTSAM stable release instead of develop, then it worked!
Instead of:
RUN add-apt-repository ppa:joseluisblancoc/gtsam-develop -y
RUN apt-get update \
&& apt-get -y install \
libqt5svg5-dev \
libgtsam-dev \
#
# Clean ups
&& apt-get autoremove -y \
&& apt-get clean -y \
&& rm -rf /var/lib/apt/lists/*
do:
RUN add-apt-repository ppa:borglab/gtsam-release-4.0 -y
RUN apt-get update \
&& apt-get -y install \
libqt5svg5-dev \
libgtsam-dev \
libgtsam-unstable-dev \
#
# Clean ups
&& apt-get autoremove -y \
&& apt-get clean -y \
&& rm -rf /var/lib/apt/lists/*
For fast test to detect the bug, just after building rtabmap library:
cd ~/rtabmap/bin
./rtabmap-console
If it crashes, do
gdb rtabmap-console
# type "run",
# then "bt" after crash
I'm getting these error messages when building the package
[Processing: rtabmap_ros]
--- stderr: rtabmap_ros
CMake Warning:
Manually-specified variables were not used by the project:
DBoW2_DIR
Pangolin_DIR
g2o_DIR
openvslam_DIR
Member name 'global' in the service request 'GetMap' is a reserved keyword in Python and is not supported at the moment. Please use a different name.
Member name 'global' in the service request 'PublishMap' is a reserved keyword in Python and is not supported at the moment. Please use a different name.
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp: In function ‘bool rtabmap_ros::convertScanMsg(const LaserScan&, const string&, const string&, const rclcpp::Time&, rtabmap::LaserScan&, tf2_ros::Buffer&, double, bool)’:
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1741:74: error: no match for ‘operator=’ (operand types are ‘cv::Mat’ and ‘rtabmap::LaserScan’)
1741 | data = rtabmap::util3d::laserScan2dFromPointCloud(*pclScan, laserToOdom); // put back in laser frame
| ^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:743:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(const cv::Mat&)’
743 | Mat& Mat::operator = (const Mat& m)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:743:34: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const cv::Mat&’
743 | Mat& Mat::operator = (const Mat& m)
| ~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:3356:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(const cv::MatExpr&)’
3356 | Mat& Mat::operator = (const MatExpr& e)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:3356:38: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const cv::MatExpr&’
3356 | Mat& Mat::operator = (const MatExpr& e)
| ~~~~~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.hpp:1241:10: note: candidate: ‘cv::Mat& cv::Mat::operator=(const Scalar&)’
1241 | Mat& operator = (const Scalar& s);
| ^~~~~~~~
/usr/include/opencv4/opencv2/core/mat.hpp:1241:36: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const Scalar&’ {aka ‘const cv::Scalar_<double>&’}
1241 | Mat& operator = (const Scalar& s);
| ~~~~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:1405:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(cv::Mat&&)’
1405 | Mat& Mat::operator = (Mat&& m)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:1405:29: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘cv::Mat&&’
1405 | Mat& Mat::operator = (Mat&& m)
| ~~~~~~^
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1749:74: error: no match for ‘operator=’ (operand types are ‘cv::Mat’ and ‘rtabmap::LaserScan’)
1749 | data = rtabmap::util3d::laserScan2dFromPointCloud(*pclScan, laserToOdom); // put back in laser frame
| ^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:743:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(const cv::Mat&)’
743 | Mat& Mat::operator = (const Mat& m)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:743:34: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const cv::Mat&’
743 | Mat& Mat::operator = (const Mat& m)
| ~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:3356:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(const cv::MatExpr&)’
3356 | Mat& Mat::operator = (const MatExpr& e)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:3356:38: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const cv::MatExpr&’
3356 | Mat& Mat::operator = (const MatExpr& e)
| ~~~~~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.hpp:1241:10: note: candidate: ‘cv::Mat& cv::Mat::operator=(const Scalar&)’
1241 | Mat& operator = (const Scalar& s);
| ^~~~~~~~
/usr/include/opencv4/opencv2/core/mat.hpp:1241:36: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘const Scalar&’ {aka ‘const cv::Scalar_<double>&’}
1241 | Mat& operator = (const Scalar& s);
| ~~~~~~~~~~~~~~^
In file included from /usr/include/opencv4/opencv2/core/mat.hpp:3724,
from /usr/include/opencv4/opencv2/core.hpp:59,
from /usr/include/opencv4/opencv2/opencv.hpp:52,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:40,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/include/opencv4/opencv2/core/mat.inl.hpp:1405:6: note: candidate: ‘cv::Mat& cv::Mat::operator=(cv::Mat&&)’
1405 | Mat& Mat::operator = (Mat&& m)
| ^~~
/usr/include/opencv4/opencv2/core/mat.inl.hpp:1405:29: note: no known conversion for argument 1 from ‘rtabmap::LaserScan’ to ‘cv::Mat&&’
1405 | Mat& Mat::operator = (Mat&& m)
| ~~~~~~^
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp: In function ‘bool rtabmap_ros::convertScan3dMsg(const PointCloud2&, const string&, const string&, const rclcpp::Time&, rtabmap::LaserScan&, tf2_ros::Buffer&, double, int, float)’:
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1842:156: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1842 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZRGBNormal, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1852:154: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1852 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZINormal, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1862:153: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1862 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZNormal, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1875:150: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1875 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZRGB, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1885:148: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1885 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZI, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:1895:147: warning: ‘rtabmap::LaserScan::LaserScan(const rtabmap::LaserScan&, int, float, rtabmap::LaserScan::Format, const rtabmap::Transform&)’ is deprecated: Use version without "format" argument. [-Wdeprecated-declarations]
1895 | scan = rtabmap::LaserScan(rtabmap::util3d::laserScanFromPointCloud(*pclScan), maxPoints, maxRange, rtabmap::LaserScan::kXYZ, scanLocalTransform);
| ^
In file included from /usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/Transform.h:31,
from /ros2_ws/src/rtabmap_ros/include/rtabmap_ros/MsgConversion.h:44,
from /ros2_ws/src/rtabmap_ros/src/MsgConversion.cpp:28:
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/LaserScan.h:78:21: note: declared here
78 | RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
| ^~~~~~~~~
/usr/local/lib/rtabmap-0.20/../../include/rtabmap-0.20/rtabmap/core/RtabmapExp.h:42:39: note: in definition of macro ‘RTABMAP_DEPRECATED’
42 | #define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
| ^~~~
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp: In member function ‘void rtabmap_ros::OdometryROS::init(bool, bool, bool)’:
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp:318:34: error: ‘class rtabmap::Odometry’ has no member named ‘canProcessIMU’; did you mean ‘canProcessAsyncIMU’?
318 | if(waitIMUToinit_ || odometry_->canProcessIMU())
| ^~~~~~~~~~~~~
| canProcessAsyncIMU
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp: In member function ‘void rtabmap_ros::OdometryROS::callbackIMU(sensor_msgs::msg::Imu_<std::allocator<void> >::SharedPtr)’:
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp:357:18: error: ‘class rtabmap::Odometry’ has no member named ‘canProcessIMU’; did you mean ‘canProcessAsyncIMU’?
357 | if(!odometry_->canProcessIMU() &&
| ^~~~~~~~~~~~~
| canProcessAsyncIMU
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp:385:18: error: ‘class rtabmap::Odometry’ has no member named ‘canProcessIMU’; did you mean ‘canProcessAsyncIMU’?
385 | if(!odometry_->canProcessIMU())
| ^~~~~~~~~~~~~
| canProcessAsyncIMU
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp: In member function ‘void rtabmap_ros::OdometryROS::processData(const rtabmap::SensorData&, const rclcpp::Time&)’:
/ros2_ws/src/rtabmap_ros/src/OdometryROS.cpp:455:17: error: ‘class rtabmap::Odometry’ has no member named ‘canProcessIMU’; did you mean ‘canProcessAsyncIMU’?
455 | if(odometry_->canProcessIMU() && data.imu().empty() && lastImuReceivedStamp_>0.0 && data.stamp() > lastImuReceivedStamp_)
| ^~~~~~~~~~~~~
| canProcessAsyncIMU
make[2]: *** [CMakeFiles/rtabmap_ros.dir/build.make:63: CMakeFiles/rtabmap_ros.dir/src/MsgConversion.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[2]: *** [CMakeFiles/rtabmap_ros.dir/build.make:89: CMakeFiles/rtabmap_ros.dir/src/OdometryROS.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:893: CMakeFiles/rtabmap_ros.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
---
Failed <<< rtabmap_ros [44.1s, exited with code 2]
This is a change done yesterday (canProcessIMU->canProcessAsyncIMU), pull latest rtabmap_ros ros2 branch: https://github.com/introlab/rtabmap_ros/commit/688584db65b6e95b176680ae765642979252d760
Console output:
[INFO] [launch]: All log files can be found below /home/vscode/.ros/log/2021-03-02-21-14-02-494762-aleksa-Vostro-7590-36189
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [rtabmap-1]: process started with pid [36194]
[INFO] [rtabmapviz-2]: process started with pid [36196]
[ERROR] [rtabmapviz-2]: process has died [pid 36196, exit code -11, cmd '/workspaces/ws_robogreen/install/rtabmap_ros/lib/rtabmap_ros/rtabmapviz --ros-args --params-file /tmp/launch_params_yvkr1e5x -r scan:=/scan'].
[ERROR] [rtabmap-1]: process has died [pid 36194, exit code -11, cmd '/workspaces/ws_robogreen/install/rtabmap_ros/lib/rtabmap_ros/rtabmap -d --ros-args --params-file /tmp/launch_params_n045s7ys -r scan:=/scan'].
gdb call stack (of [rtabmap-1]):
libc.so.6!free (Unknown Source:0)
libg2o_types_slam2d.so!g2o::EdgeSE2PointXYCalib::~EdgeSE2PointXYCalib() (Unknown Source:0)
libg2o_core.so!g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (Unknown Source:0)
libg2o_types_slam2d.so!__static_initialization_and_destruction_0(int, int) [clone .constprop.0] (Unknown Source:0)
ld-linux-x86-64.so.2![Unknown/Just-In-Time compiled code] (Unknown Source:0)
It seems crashing on another Factory::registerType. Let me rebuild your dockerfile with gtsam stable release and -DBUILD_WITH_MARCH_NATIVE=OFF
.
This and -DBUILD_WITH_MARCH_NATIVE=OFF
seemed to have worked. It launches without any errors now. I will try out the other launch files to make sure everything works. Thank you very much!
Hello,
At the beginning of February, rtabmap was working without any issues, but around two weeks ago I started having problems. When trying to launch anything I started getting
double free or corruption (out)
. If I only launch rtabmap without the simulation it does not crash, but as soon as it tries to subscribe to an existing topic it crashes.Ubuntu 20.04 ROS2 Foxy Everything is running inside a Docker container. The same error occurred on another pc when doing the same steps (same Dockerfile).
I have tried the suggestion from #505, but it crashes even faster. Changing
-DBUILD_WITH_MARCH_NATIVE
toOFF
has the same effect. Installing Eigen and GTSAM from the source also didn't help. When launching the node with gdb I get a lot of Eigen callback errors.When executing:
I get this output:
Cmake output:
Dockerfile: