How to add keyframe when RTABMap is built?

classic Classic list List threaded Threaded
6 messages Options
Reply | Threaded
Open this post in threaded view
|

How to add keyframe when RTABMap is built?

yincanben
Hi, matlabbe,
     RTABMap could remove dynamic objects when loop closure is detected. But it can,t remove whole dynamic objects. I have achieve a model for removing dynamic objects. I want to add it to RTABMap projects to test performance of removing dynamic objects when map is built.  I want to know that how to add keyframe in the processing of building map. which piece code should I look up? Thank you!
Reply | Threaded
Open this post in threaded view
|

Re: How to add keyframe when RTABMap is built?

matlabbe
Administrator
Hello,

On which step are you filtering the dynamic objects? If you are detecting dynamic obstacles using the depth images of the kinect, you could put your node to filter the depth image input of rtabmap by setting depth pixels of the dynamic object to 0. In that way, when new node are added to the map, the dynamic depth pixels won't be shown. Example:

/camera/rgb/image_color_rect -------------------------------------------------------------------------------
                                                                                                            \
/camera/rgb/camera_info  ---------------------------------------------------------------------------------   \
                                                                                                          \   \
/camera/depth_registered/image_raw  ---> [my_dynamic_objects_removal_node] ---> /depth_filtered ---->  [rtabmap_node]

In the code, you could modify the input of:
-Standalone: rtabmap::process()
-ROS: CoreWrapper::process()

Note: I recommend to use an external node approach instead of modifying the functions above, the code interface has changed slightly in devel branch.

cheers
Reply | Threaded
Open this post in threaded view
|

Re: How to add keyframe when RTABMap is built?

phke
Hello Mathieu,

I am working on ROS with rtabmap.

matlabbe wrote
In the code, you could modify the input of:
-Standalone: rtabmap::process()
-ROS: CoreWrapper::process()
My question is: where in the code can I modify the input of CoreWrapper::process()?
Or, to put the question in a different way: where in the current code is the input for CoreWrapper::process() generated?

Thanks for all your great work!
Philipp
Reply | Threaded
Open this post in threaded view
|

Re: How to add keyframe when RTABMap is built?

matlabbe
Administrator
You can look for CoreWrapper::commonDepthCallbackImpl(), the depth image is transferred to a SensorData object just there.

But as I noted in the previous post, it can be easier to just create a node filtering the depth image before feeding it to rtabmap.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How to add keyframe when RTABMap is built?

phke
Thank you for the reply. But where in the source code is the decision made, which image of the incoming image topic stream is considered. If I got it right, in CodeWrapper::defaultCallback() the method only starts to do something if
ros::Time::now() - time_ == ros::Duration(1.0f/rate_). Where can I find a similar condition in the case that an RGBD-Camera is connected?

Thank you very much,
Philipp
Reply | Threaded
Open this post in threaded view
|

Re: How to add keyframe when RTABMap is built?

matlabbe
Administrator
It is in the odomUpdate() or odomTFUpdate() functions here and here.

The rate can be set with parameter Rtabmap/DetectionRate:
<node pkg="rtabmap_ros" type="rtabmap" ...
   <param name="Rtabmap/DetectionRate" value="1.0"/> <!-- Hz -->
   ...