Build a map with the image transformed wirelessly

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

Build a map with the image transformed wirelessly

JaneLee
Hello:
     I am trying to use the rtabmap in the quadrotor, my idea is transform the image received by kinect wireless to the ground station. The quadrotor has a onboard computer. The ground station was set as master.  My router bandwidth is 500M(5g Hz). I use the "rostopic hz" command to test the frequency, it was about 10 Hz. But when I launch the rtabmap_ros rgbd_mapping.launch file, the update frequency is very slow. The output is as follow:

[ INFO] [1430133432.112759461]: Odom: quality=103, std dev=0.002801m, update time=0.012454s
[ WARN] [1430133432.123428080]: Lookup would require extrapolation into the future.  Requested time 1430133432.357551120 but the latest data is at time 1430133432.121763074, when looking up transform from frame [camera_rgb_optical_frame] to frame [base_link]
[ INFO] [1430133432.130238308]: rtabmap: Update rate=1.000000s, Limit=0.000000s, RTAB-Map=0.016682s, Publish=0.000446s (1 local nodes)
[ WARN] [1430133432.258978169]: Lookup would require extrapolation into the future.  Requested time 1430133432.489575084 but the latest data is at time 1430133432.121763074, when looking up transform from frame [camera_rgb_optical_frame] to frame [base_link]
[ WARN] [1430133432.437728873]: Lookup would require extrapolation into the future.  Requested time 1430133432.657540336 but the latest data is at time 1430133432.121763074, when looking up transform from frame [camera_rgb_optical_frame] to frame [base_link]
Could you please give me some advices?Thank you!
Reply | Threaded
Open this post in threaded view
|

Re: Build a map with the image transformed wirelessly

matlabbe
Administrator
Hello,

I assume that you are running rtabmap on the ground station. The update frequency of the odometry seems enough fast (0.012454s ~ 80Hz).

The rtabmap node is processing pretty fast too (0.016682s ~ 60 Hz) on the beginning. Are you referring to the rtabmap's update rate of 1 second? 1 Hz is the default update rate of RTAB-Map. Well, in my experiments, 1 Hz is enough to get a satisfying 3D map without using too much computation power. However, you can still increase this rate using the parameter "Rtabmap/DetectionRate", for example to 2 Hz:
   <param name="Rtabmap/DetectionRate" type="string" value="2"/>

Note that rtabmap node computation time is not bounded if the time limit is not set (as in your configuration where "Limit=0.000000s"). So the time shown in "RTAB-Map=0.016682s" will eventually get over the update rate. If you increase "Rtabmap/DetectionRate", your system will not be online at some point. To set the time limit to keep the mapping node online, set the parameter "Rtabmap/TimeThr" too. Refer to this paper to know what are the consequences of setting this time limit. Here some examples depending on the detection rate:
   <param name="Rtabmap/DetectionRate" type="string" value="0.5"/> <!-- 2000 ms -->
   <param name="Rtabmap/TimeThr" type="string" value="1600"/>

   <param name="Rtabmap/DetectionRate" type="string" value="1"/> <!-- 1000 ms -->
   <param name="Rtabmap/TimeThr" type="string" value="700"/>

   <param name="Rtabmap/DetectionRate" type="string" value="2"/> <!-- 500 ms -->
   <param name="Rtabmap/TimeThr" type="string" value="400"/>

   <param name="Rtabmap/DetectionRate" type="string" value="5"/> <!-- 200 ms -->
   <param name="Rtabmap/TimeThr" type="string" value="150"/>

While I don't recommend it, but for testing, you can set "Rtabmap/DetectionRate" to 0 to make rtabmap node processing data as fast as it can.

cheers
Reply | Threaded
Open this post in threaded view
|

Re: Build a map with the image transformed wirelessly

Whiss
In reply to this post by JaneLee
Hi!

I'm not sure about this, but I had the same type of warning whith two communicating computers which dates weren't synchronized. Have you tried to sync them using the command-line tool "date --set ..."?
Reply | Threaded
Open this post in threaded view
|

Re: Build a map with the image transformed wirelessly

matlabbe
Administrator

To synchronize the clock between two computers connected to internet, this can be used on both computers:
sudo ntpdate time.nist.gov

I think you can synchronize with another computer directly if they don't have internet, like :
sudo ntpdate 192.168.1.3
where "192.168.1.3" is the other computer on the network.

Indeed, the TF time stamps should be synchronized between the computers.