[ros-users] Sync problem with stereo_image_proc
Sacha Aury
sacha at shadowrobot.com
Fri May 21 16:15:13 UTC 2010
Dear Radu
Thanks for your help. Since my connection at work is not really fast, I
will send the bag on http://fly.yozora-irc.net/shadow tonight. You can
already see my disparity map and both left / right images at this place.
Cheers,
Sacha
Le vendredi 21 mai 2010 à 08:55 -0700, Radu Bogdan Rusu a écrit :
> Dear Sacha,
>
> Can you assemble a bag file with the following topics? Please replace "mystereo" with the name of your stereo camera:
> /mystereo/left/image_raw
> /mystereo/left/camera_info
> /mystereo/right/image_raw
> /mystereo/right/camera_info
>
> and upload it somewhere where I can access it?
>
> In the meantime, can you make a screenshot of the disparity image? Just visualize it using image_view, and save it to a
> jpg/png.
>
> Thanks,
> Radu.
>
> On 05/21/2010 02:41 AM, Sacha Aury wrote:
> > Dear Radu,
> >
> > Even if I understand that having some not valid disparity values is
> > possible, I actually do not have any good ones. Moreover, all my points
> > are quite the same (0.0, 0.0, nan) which is a bit strange I think. What
> > could I do to fix this ? I already tried to change parameters with
> > dynamic_reconfigure, but it did not change anything.
> >
> > Cheers,
> > Sacha
> >
> > Le jeudi 20 mai 2010 à 10:45 -0700, Radu Bogdan Rusu a écrit :
> >> Dear Sacha,
> >>
> >> What you're seeing makes sense. Though your disparity "looks good", I am sure you don't have valid disparity values at
> >> each pixel in the disparity image. None of us do :). What you are seeing as the output of rostopic echo is the list of
> >> 3D points that do not have valid disparity values (we mark those with nan).
> >>
> >> Cheers,
> >> Radu.
> >>
> >> On 05/20/2010 09:37 AM, Sacha Aury wrote:
> >>> I do not really understand why, but I looked to the TF tutorial, added a
> >>> few things to my program and rviz do not complain anymore. To recap, I
> >>> now have a disparity map, rviz do not complain about a fixed_frame, but
> >>> my goal is to get the points cloud. Rviz warns :
> >>> [ WARN] 1274372115.122808000: TF_OLD_DATA ignoring data from the past
> >>> for frame /test at time 16566 according to authority /camera_sync
> >>> Possible reasons are listed at
> >>>
> >>>
> >>>
> >>> $rostopic echo /stereo/points | less :
> >>> header:
> >>> seq: 937
> >>> stamp: 18596000000000
> >>> frame_id: fixed_frame
> >>> points: [
> >>> x: 0.0
> >>> y: 0.0
> >>> z: nan,
> >>> x: 0.0
> >>> y: 0.0
> >>> z: nan,
> >>> x: 0.0
> >>> y: 0.0
> >>> z: nan,
> >>> x: 0.0
> >>> y: 0.0
> >>> z: nan,
> >>> x: 0.0
> >>> y: 0.0
> >>> z: nan,
> >>> x: 0.0
> >>>
> >>> I don't get it, since my disparity map looks good. I can send you a
> >>> screenshot of the map if you need it.
> >>> So, why is the processing not sending the good coords ? I did not
> >>> calibrate my cameras since I did not find a way to do it for stereo
> >>> vision, is there a problem with that ?
> >>>
> >>> Thanks.
> >>>
> >>> Le mercredi 19 mai 2010 à 10:38 -0700, Josh Faust a écrit :
> >>>> If you don't have a TF transform tree (http://ros.org/wiki/tf), the
> >>>> fixed frame needs to match the frame you've set. You also need to set
> >>>> the timestamp in the header.
> >>>>
> >>>> msg.header.stamp = ros::Time::now();
> >>>>
> >>>> Josh
> >>>>
> >>>> On Wed, May 19, 2010 at 7:53 AM, Sacha Aury<sacha at shadowrobot.com>
> >>>> wrote:
> >>>> Thanks for your help. I now have a single node synchronizing
> >>>> my two
> >>>> cameras (image and infos). It works with the stereo_view and I
> >>>> get the
> >>>> disparity map, which I am configuring. My question is now
> >>>> about rviz,
> >>>> which I've never used. It seems to need a fixed frame to
> >>>> display my 3D
> >>>> cloud points. I tried to set a frame_id in my synchronization
> >>>> node
> >>>> (before broadcasting it to stereo_image_proc), but it does not
> >>>> work,
> >>>> rviz still can't get any fixed frame.
> >>>>
> >>>> How can I do that ? I think I am close to the result, but I
> >>>> can't see
> >>>> it !
> >>>>
> >>>> Le mardi 18 mai 2010 à 09:07 -0700, Blaise Gassend a écrit :
> >>>>
> >>>> > Hi Sacha,
> >>>> >
> >>>> > stereo_image_proc doesn't care about when your message was
> >>>> published, it
> >>>> > just cares about the timestamp in the message. So your
> >>>> republishing node
> >>>> > needs to set the timestamp, both in the image topic and in
> >>>> the
> >>>> > camera_info topic.
> >>>> >
> >>>> > Blaise
> >>>> >
> >>>> > On Tue, 2010-05-18 at 16:29 +0100, Sacha Aury wrote:
> >>>> > > I think that having a hardware solution is a bit overkill
> >>>> for my
> >>>> > > problem. So I tried to write a node which collected image
> >>>> messages from
> >>>> > > my two cameras and which published both message every x
> >>>> seconds,
> >>>> > > typically 1/2. And when I am using
> >>>> image_pipeline/stereo_image_proc, I
> >>>> > > got messages of that kind :
> >>>> > >
> >>>> > > [ WARN] 1274196325.866264000: [stereo_image_proc] Low
> >>>> number of
> >>>> > > synchronized left/right image pairs received.
> >>>> > > Left images received: 831
> >>>> > > Right images received: 831
> >>>> > > Synchronized pairs: 0
> >>>> > > Possible issues:
> >>>> > > * The cameras are not synchronized.
> >>>> > > * The network is too slow. For each synchronized image
> >>>> pair, at most 1
> >>>> > > is getting through.
> >>>> > >
> >>>> > > I don't know what I could do more, since the
> >>>> synchronisation should be
> >>>> > > done by a TimeSynchronizer in the stereo_image_proc class.
> >>>> Could it be
> >>>> > > posible to cheat on the timestamps in any way ?
> >>>> > >
> >>>> > > Thanks, and sorry for the double post, I made a mistake at
> >>>> first.
> >>>> > >
> >>>> > > Le lundi 17 mai 2010 à 07:53 -0700, Gary Bradski a écrit :
> >>>> > > > What level do you want synchronization on? Within
> >>>> framerate (both
> >>>> > > > frames happen randomly but within 1/30 of a second of
> >>>> each other) or
> >>>> > > > exact frame synchronization? The first is achievable,
> >>>> the second needs
> >>>> > > > extra hardware.
> >>>> > > >
> >>>> > > > At most, ROS can get you timestamps to align to, but to
> >>>> get actual
> >>>> > > > simultaneous frames, you'll need a triggering signal in
> >>>> hardware such
> >>>> > > > as a wire between 2 cameras (that allow for this). Some
> >>>> 1394 cameras
> >>>> > > > may allow triggering over the 1394 bus and then you'll
> >>>> only have the
> >>>> > > > problem of getting both buses to trigger at the same
> >>>> time ... which
> >>>> > > > may be approximately possible, most of the time ... on
> >>>> average.
> >>>> > > > Depends on the driver and the 1394 port.
> >>>> > > >
> >>>> > > > I've seen an automotive 1394 article (not ROS related)
> >>>> where they have
> >>>> > > > about 10 cameras. The cameras run the cameras at very
> >>>> high framerates
> >>>> > > > and then they do timestamp synchronization which allows
> >>>> fairly
> >>>> > > > synchronous alignment of multiple with no extra
> >>>> hardware.
> >>>> > > >
> >>>> > > > Gary
> >>>> > > >
> >>>> > > > On Mon, May 17, 2010 at 5:23 AM, Sacha Aury
> >>>> <sacha at shadowrobot.com>
> >>>> > > > wrote:
> >>>> > > > Hi,
> >>>> > > >
> >>>> > > > I am trying to make a stereo camera acquisition
> >>>> using ROS with
> >>>> > > > the
> >>>> > > > cameradc1394 driver and the stereo_proc package.
> >>>> I've got a
> >>>> > > > separate
> >>>> > > > computer to stream the image_raw from my two
> >>>> cameras. The
> >>>> > > > stream works,
> >>>> > > > but when I launch stereo_image_proc, it seems
> >>>> that my two
> >>>> > > > cameras are
> >>>> > > > not synchronized :
> >>>> > > >
> >>>> > > > [ WARN] 1274098675.074074000:
> >>>> [stereo_image_proc] Low number
> >>>> > > > of
> >>>> > > > synchronized left/right image pairs received.
> >>>> > > > Left images received: 3079
> >>>> > > > Right images received: 3076
> >>>> > > > Synchronized pairs: 0
> >>>> > > > Possible issues:
> >>>> > > > * The cameras are not synchronized.
> >>>> > > > * The network is too slow. For each
> >>>> synchronized image
> >>>> > > > pair, at most 1
> >>>> > > > is getting through.
> >>>> > > >
> >>>> > > > Here is my launch file :
> >>>> > > >
> >>>> > > > <!-- startstream.launch -->
> >>>> > > > <launch>
> >>>> > > > <param name="display" type="int"
> >>>> value="0"/>
> >>>> > > > <param name="framerate" type="double"
> >>>> value="15"/>
> >>>> > > > <param name="mode"
> >>>> value="MODE_320x240_YUV422"/>
> >>>> > > >
> >>>> > > > <node name="camera_left" pkg="cameradc1394"
> >>>> > > > type="cameradc1394"
> >>>> > > > respawn="true">
> >>>> > > > <param name="prefix" type="string"
> >>>> > > > value="/stereo/left/"/>
> >>>> > > > <param name="cameraindex" type="int"
> >>>> value="0"/>
> >>>> > > > </node>
> >>>> > > >
> >>>> > > >
> >>>> > > > <node name="camera_right" pkg="cameradc1394"
> >>>> > > > type="cameradc1394"
> >>>> > > > respawn="true">
> >>>> > > > <param name="prefix" type="string"
> >>>> > > > value="/stereo/right/"/>
> >>>> > > > <param name="cameraindex" type="int"
> >>>> value="1"/>
> >>>> > > > </node>
> >>>> > > >
> >>>> > > > </launch>
> >>>> > > >
> >>>> > > > Is there any specific way to make the two
> >>>> cameras
> >>>> > > > synchronize ?
> >>>> > > >
> >>>> > > > I am following that tutorial :
> >>>> > > >
> >>>> > > > http://www.ros.org/wiki/stereo_image_proc
> >>>> > > >
> >>>> > > > Thank you for any help.
> >>>> > > >
> >>>> > > > Sacha
> >>>> > > >
> >>>> > > >
> >>>> > > > _______________________________________________
> >>>> > > > ros-users mailing list
> >>>> > > > ros-users at code.ros.org
> >>>> > > > https://code.ros.org/mailman/listinfo/ros-users
> >>>> > > >
> >>>> > > > _______________________________________________
> >>>> > > > ros-users mailing list
> >>>> > > > ros-users at code.ros.org
> >>>> > > > https://code.ros.org/mailman/listinfo/ros-users
> >>>> > >
> >>>> > >
> >>>> > > _______________________________________________
> >>>> > > ros-users mailing list
> >>>> > > ros-users at code.ros.org
> >>>> > > https://code.ros.org/mailman/listinfo/ros-users
> >>>> >
> >>>> >
> >>>> > _______________________________________________
> >>>> > ros-users mailing list
> >>>> > ros-users at code.ros.org
> >>>> > https://code.ros.org/mailman/listinfo/ros-users
> >>>>
> >>>>
> >>>> _______________________________________________
> >>>> ros-users mailing list
> >>>> ros-users at code.ros.org
> >>>> https://code.ros.org/mailman/listinfo/ros-users
> >>>>
> >>>>
> >>>> _______________________________________________
> >>>> ros-users mailing list
> >>>> ros-users at code.ros.org
> >>>> https://code.ros.org/mailman/listinfo/ros-users
> >>>
> >>>
> >>> _______________________________________________
> >>> ros-users mailing list
> >>> ros-users at code.ros.org
> >>> https://code.ros.org/mailman/listinfo/ros-users
> >>
> >
> >
>
More information about the ros-users
mailing list