Hi Mathieu,
I followed your tutorial to bring up RTAB-Map with ASUS Xtion + Odometry (laser scan disabled) and I prepared the following launch file for my experiments: <launch> <!-- Low-level motor interface (provides wheel odometry and tf) --> <node pkg="motor_serial_driver" type="motor_serial_driver" name="motor_serial_driver" output="screen" required="true" args="/dev/ttyS0 115200"/> <!-- ASUS Xtion Pro driver node --> <include file="$(find openni2_launch)/launch/openni2.launch"> <arg name="depth_registration" value="true"/> </include> <!-- Visualization mode --> <arg name="rviz" default="false" /> <arg name="rtabmapviz" default="true" /> <!-- RTAB-Map --> <group ns="rtabmap"> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start"> <!-- Fixed frame on the robot --> <param name="frame_id" type="string" value="base_link"/> <remap from="odom" to="/base_controller/odom"/> <!-- Depth information from sensors --> <param name="subscribe_depth" type="bool" value="true"/> <remap from="rgb/image" to="/camera/rgb/image_rect_color"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <!--<param name="subscribe_laserScan" type="bool" value="true"/>--> </node> <!-- Visualisation RTAB-Map --> <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen"> <param name="subscribe_depth" type="bool" value="true"/> <!--<param name="subscribe_laserScan" type="bool" value="true"/>--> <param name="frame_id" type="string" value="base_link"/> <param name="wait_for_transform" type="bool" value="true"/> <remap from="rgb/image" to="/camera/rgb/image_rect_color"/> <remap from="depth/image" to="/camera/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/> <remap from="odom" to="/base_controller/odom"/> <param name="rgb/image_transport" type="string" value="compressed"/> <param name="depth/image_transport" type="string" value="compressedDepth"/> </node> </group> </launch>The first node provides the interface to the motors and computes the odometry, while the second starts the Xtion sensor. The rtabmap and rtabmapviz nodes are configured according to your tutorials. When I launch this file the output, it seems everything starts correctly, since after all the initialization messages I receive the message "rtabmap 0.10.4 started..." and rtabmapviz shows up on the monitor, but it does not display either the 3D map or the graph, this is a screenshot: And these are the node connections: Do you have an idea of what am I doing wrong? Thanks in advance! PS: launching "rtabmap" standalone works perfectly, I tested it for over two weeks, now I just want to integrate it at least with real odometry from motors.
~Guido
|
Administrator
|
Hi,
Are the input messages published? $ rostopic hz /base_controller/odom $ rostopic hz /camera/rgb/image_rect_color $ rostopic hz /camera/depth_registered/image_raw $ rostopic hz /camera/rgb/camera_info and you can remove: <param name="rgb/image_transport" type="string" value="compressed"/> <param name="depth/image_transport" type="string" value="compressedDepth"/> cheers |
Good point, camera topics were correctly publishing at 25 Hz, but the odometry was stuck, because my driver node was publishing "/odom" and not "/base_controller/odom". I corrected the <remap> in launch file, thanks for pointing it out!
However, after restarting my launch file, the log now shows this and still nothing is displayed: /rtabmap/rtabmap subscribed to: /camera/rgb/image_rect_color, /camera/depth_registered/image_raw, /camera/rgb/camera_info, /odom [INFO] [1442573630.949665648]: rtabmap 0.10.4 started... [WARN] [1442573632.285153021]: Could not get transform from base_link to camera_rgb_optical_frame after 1 second!Do you have an idea also about this? PS: sorry, I'm a beginner with ROS, I've learned the basics, but still miss some points about tf, frames and launch files, so I need some more advice than ROS experts, many thanks in advance! ;)
~Guido
|
Administrator
|
Hi,
you can debug your TF tree using: $ rosrun tf view_frames $ evince frames.pdf I common TF tree is : /map -> /odom -> /base_link -> /camera_link -> /camera_rgb_optical_frame: 1. /camera_link -> /camera_rgb_optical_frame is published by openni2 2. /base_link -> /camera_link is published by a static_transform_publisher or a robot_state_publisher. Example: <node pkg="tf" type="static_transform_publisher" name="base_to_camera" args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /camera_link 100" />3. /odom -> /base_link is published by your odometry node 4. /map -> /odom is published by rtabmap cheers |
Hi Mathieu,
I did what you suggested, and here is what is shown while the launch file is running and the "Could not get transform..." warning is displayed: Other than the camera rate is low (10 Hz) and odometry rate is high (50 Hz), I do not see and /map topic published, is it normal? Many thanks!
~Guido
|
Administrator
|
The /map frame will be be published when rtabmap is running (when input messages are received and TF is valid). In your case, the /base_link is not connected to /camera_link, did you add this in your launch file?
<node pkg="tf" type="static_transform_publisher" name="base_to_camera" args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /camera_link 100" /> |
Yeah, it was that! I forgot the tf node in the launch file, shame on me... :)
Now this is the new tf graph and now RTAB-Map Viz displays the 3D data coming from the sensor. I'm using teleoperation to move my robot and now it's pose in RTAB-Map Viz is correctly updated... many many thanks! Next step is to map the indoor environment, go into localization mode and use "move_base" to test the navigation stack.
~Guido
|
Free forum by Nabble | Edit this page |