Closed void-robotics closed 4 years ago
Hi,
I am not sure why it is subscribing to imu, as it should not using the command you provided. Just tried latest ros-melodic-rtabmap-ros and no problems with this command:
$ rosrun rtabmap_ros rtabmap _subscribe_scan:=true _subscribe_rgb:=false _subscribe_depth:=false _approx_sync:=true -d
approx_sync should be true as /odom
and /scan
topics would not have the same stamps.
Make sure the old rtabmap libraries are not in the PATH, when using the binaries (to avoid crashes with wrong library version loaded). You can try this to make sure your catkin_ws with local rtabmap is not in the PATH:
$ source /opt/ros/melodic/setup.bash
$ $ rosrun rtabmap_ros rtabmap _subscribe_scan:=true _subscribe_rgb:=false _subscribe_depth:=false _approx_sync:=true -d
cheers, Mathieu
Now instead of the seg fault, I'm not sure how to remap the camera topic paths (not using lidar), as this isn't working:
rosrun rtabmap_ros rtabmap _subscribe_scan:=false _subscribe_rgb:=true _subscribe_depth:=true _approx_sync:=true _rgb_topic:=/camera/rgb/image_raw _depth_topic:=/camera/depth/image_raw _camera_info_topic:=/camera/rgb/camera_info _depth_camera_info_topic:=/camera/depth/camera_info -d
...
[N=/rtabmap,F=main-95]: rtabmap 0.19.3 started...
[N=/rtabmap,F=CommonDataSubscriber::warningLoop-783]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
/odom,
/rgb/image,
/depth/image,
/rgb/camera_info
Instead I created a launch file, and it finds the right topics but then it crashes:
[N=/rtabmap/rtabmap,F=main-95]: rtabmap 0.19.5 started...
[N=/rtabmap/rtabmap,F=CommonDataSubscriber::warningLoop-783]: /rtabmap/rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called.
/rtabmap/rtabmap subscribed to (exact sync):
/odom,
/camera/rgb/image_raw,
/camera/depth/image_raw,
/camera/rgb/camera_info
[rtabmap/rtabmap-2] process has died [pid 12956, exit code -11, cmd /home/nathan/newmind/devel/lib/rtabmap_ros/rtabmap -d rgb/image:=/camera/rgb/image_raw depth/image:=/camera/depth/image_raw rgb/camera_info:=/camera/rgb/camera_info rgbd_image:=rgbd_image left/image_rect:=/stereo_camera/left/image_rect_color right/image_rect:=/stereo_camera/right/image_rect left/camera_info:=/stereo_camera/left/camera_info right/camera_info:=/stereo_camera/right/camera_info scan:=/scan scan_cloud:=/scan_cloud user_data:=/user_data user_data_async:=/user_data_async gps/fix:=/gps/fix tag_detections:=/tag_detections odom:=/odom imu:=/imu/data __name:=rtabmap __log:=/home/nathan/.ros/log/510c6ae2-5d98-11ea-9633-080027519de6/rtabmap-rtabmap-2.log].
log file: /home/nathan/.ros/log/510c6ae2-5d98-11ea-9633-080027519de6/rtabmap-rtabmap-2*.log
^C[rtabmap/rgbd_sync-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done
nathan@nathan-vm:~/newmind$ roslaunch nm_navigation Rtabmap.launch
Rtabmap.launch
<?xml version="1.0"?>
<launch>
<!-- Newmind -->
<arg name="using_camera" default="true" />
<arg name="sensor_brand" default="astra" />
<arg name="motor_type" default="gazebo" />
<arg name="rtabmap_args" default="-d" />
<arg name="database_path" default="" />
<!-- Sensor topics -->
<arg if="$(eval sensor_brand == 'zed')" name="rgb_topic" default="/zed/zed_node/rgb/image_rect_color" />
<arg if="$(eval sensor_brand == 'zed')" name="depth_topic" default="/zed/zed_node/depth/depth_registered" />
<arg if="$(eval sensor_brand == 'zed')" name="camera_info_topic" default="/zed/zed_node/rgb/camera_info" />
<arg if="$(eval sensor_brand == 'zed')" name="depth_camera_info_topic" default="/zed/zed_node/depth/camera_info" />
<arg if="$(eval sensor_brand == 'astra')" name="rgb_topic" default="/camera/rgb/image_raw" />
<arg if="$(eval sensor_brand == 'astra')" name="depth_topic" default="/camera/depth/image_raw" />
<arg if="$(eval sensor_brand == 'astra')" name="camera_info_topic" default="/camera/rgb/camera_info" />
<arg if="$(eval sensor_brand == 'astra')" name="depth_camera_info_topic" default="/camera/depth/camera_info" />
<!-- Rtabmp -->
<arg name="subscribe_scan" default="false" />
<arg name="subscribe_rgbd" default="false" />
<arg name="stereo" default="false" />
<arg name="rgbd_sync" default="true" />
<arg name="approx_sync" default="true" />
<!-- Lidar Nodes -->
<group ns="rtabmap" if="$(eval using_camera == false)" >
<node unless="$(eval motor_type == 'gazebo')" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" />
<remap from="scan" to="/scan"/>
<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">
<param name="database_path" type="string" value="$(arg database_path)"/>
<param name="subscribe_scan" value="true"/>
<param name="subscribe_rgb" value="false"/>
<param name="subscribe_depth" value="false"/>
<param name="frame_id" value="base_link"/>
<param name="odom_frame_id" value="odom"/>
<param name="wait_for_transform_duration" value="1"/>
<param name="odom_tf_linear_variance" value="0.01"/>
<param name="odom_tf_angular_variance" value="0.05"/>
<param name="Reg/Strategy" value="1"/> <!-- 1 for lidar -->
<param name="Reg/Force3DoF" value="true"/> <!-- 2d slam -->
<param name="RGBD/NeighborLinkRefining" value="true"/> <!-- odometry correction with scans -->
</node>
</group>
<!-- Camera Nodes -->
<include if="$(eval using_camera == true)" file="$(find rtabmap_ros)/launch/rtabmap.launch">
<arg name="rtabmap_args" value="$(arg rtabmap_args)" />
<arg name="database_path" value="$(arg database_path)" />
<arg name="rgb_topic" value="$(arg rgb_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="camera_info_topic" value="$(arg camera_info_topic)" />
<arg name="depth_camera_info_topic" value="$(arg depth_camera_info_topic)" />
<arg name="frame_id" value="base_link" />
<arg name="approx_sync" value="false" />
<arg name="visual_odometry" value="false" />
<arg name="odom_topic" value="/odom" />
<arg name="rviz" value="false" />
<arg name="rtabmapviz" value="false" />
<arg name="subscribe_scan" value="$(arg subscribe_scan)" />
<arg name="subscribe_rgbd" value="$(arg subscribe_rgbd)" />
<arg name="stereo" value="$(arg stereo)" />
<arg name="rgbd_sync" value="$(arg rgbd_sync)" />
</include>
</launch>
I also made sure the old rtabmap wasn't in $ROS_PACKAGE_PATH by deleting both the local rtabmap and rtabmap_ros. Is deleting them not enough? I tried to do the sourcing of the opt version but then I can't start my launch file.
Well, rosrun and roslaunch seem finding different rtabmap versions: 0.19.3 and 0.19.5 respectively.
For the rosrun command you used with the binaries (0.19.3), the image topics are remaps when launching rtabmap
node directly, not parameters like with rtabmap.launch
. Try instead:
$ rosrun rtabmap_ros rtabmap \
_approx_sync:=true \
rgb/image:=/camera/rgb/image_raw \
depth/image:=/camera/depth/image_raw \
rgb/camera_info:=/camera/rgb/camera_info \
-d
cheers, Mathieu
I actually did nothing but update rtabmap and it's working! I need to run one final test on a fresh VM, which might take a few days, and I'll update this then.
Not sure what I did but the bugs are gone using 0.19.3, which appears to be the latest version in apt.
I'm getting the Seg Fault again with 0.19.6; here is my launch setup using a Zed 1 on the Jetson Nano:
roslaunch zed_wrapper zed_camera.launch
rosrun rtabmap_ros rgbd_odometry rgb/image:=/zed_node/left/image_rect_color depth/image:=/zed_node/depth/depth_registered rgb/camera_info:=/zed_node/left/camera_info
rosrun rtabmap_ros rtabmap rgb/image:=/zed_node/left/image_rect_color depth/image:=/zed_node/depth/depth_registered rgb/camera_info:=/zed_node/left/camera_info -d
This is the output:
nvidia@nm-nano:~/newmind$ rosrun rtabmap_ros rtabmap rgb/image:=/zed/zed_node/left/image_rect_color depth/image:=/zed/zed_node/depth/depth_registered rgb/camera_info:=/zed/zed_node/left/camera_info -d
[N=${node},F=main-39]: Starting node...
[N=/rtabmap,F=Loader::Impl::advertiseRosApi-233]: Initializing nodelet with 4 worker threads.
[N=/rtabmap,F=init-123]: /rtabmap(maps): map_filter_radius = 0.000000
[N=/rtabmap,F=init-124]: /rtabmap(maps): map_filter_angle = 30.000000
[N=/rtabmap,F=init-125]: /rtabmap(maps): map_cleanup = true
[N=/rtabmap,F=init-126]: /rtabmap(maps): map_always_update = false
[N=/rtabmap,F=init-127]: /rtabmap(maps): map_empty_ray_tracing = true
[N=/rtabmap,F=init-128]: /rtabmap(maps): cloud_output_voxelized = true
[N=/rtabmap,F=init-129]: /rtabmap(maps): cloud_subtract_filtering = false
[N=/rtabmap,F=init-130]: /rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[N=/rtabmap,F=init-146]: /rtabmap(maps): octomap_tree_depth = 16
[N=/rtabmap,F=CoreWrapper::onInit-192]: rtabmap: frame_id = base_link
[N=/rtabmap,F=CoreWrapper::onInit-203]: rtabmap: map_frame_id = map
[N=/rtabmap,F=CoreWrapper::onInit-204]: rtabmap: use_action_for_goal = false
[N=/rtabmap,F=CoreWrapper::onInit-205]: rtabmap: tf_delay = 0.050000
[N=/rtabmap,F=CoreWrapper::onInit-206]: rtabmap: tf_tolerance = 0.100000
[N=/rtabmap,F=CoreWrapper::onInit-207]: rtabmap: odom_sensor_sync = false
[N=/rtabmap,F=CoreWrapper::onInit-491]: RTAB-Map detection rate = 1.000000 Hz
[N=/rtabmap,F=CoreWrapper::onInit-519]: rtabmap: Deleted database "/home/nvidia/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[N=/rtabmap,F=CoreWrapper::onInit-525]: rtabmap: Using database from "/home/nvidia/.ros/rtabmap.db" (0 MB).
[N=/rtabmap,F=CoreWrapper::onInit-550]: rtabmap: Database version = "0.19.3".
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-372]: /rtabmap: subscribe_depth = true
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-373]: /rtabmap: subscribe_rgb = true
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-374]: /rtabmap: subscribe_stereo = false
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-375]: /rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-376]: /rtabmap: subscribe_odom_info = false
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-377]: /rtabmap: subscribe_user_data = false
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-378]: /rtabmap: subscribe_scan = false
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-379]: /rtabmap: subscribe_scan_cloud = false
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-380]: /rtabmap: queue_size = 10
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-381]: /rtabmap: approx_sync = true
[N=/rtabmap,F=CommonDataSubscriber::setupDepthCallbacks-339]: Setup depth callback
[N=/rtabmap,F=CommonDataSubscriber::setupCallbacks-501]:
/rtabmap subscribed to (approx sync):
/odom,
/zed/zed_node/left/image_rect_color,
/zed/zed_node/depth/depth_registered,
/zed/zed_node/left/camera_info
[N=/rtabmap,F=main-95]: rtabmap 0.19.6 started...
Segmentation fault (core dumped)
nvidia@nm-nano:~/newmind$
I was able to fix the seg fault by deleting the local build of rtabmap (#225), but now I have a new error, the same one as #190.
Hello,
I think a recent change introduced a seg fault. In switching between an older rtabmap and rtabmap_ros locally and the most recent using apt, the one from apt gives this error:
This same command works fine for my local version.
Here is my Gazebo setup: