ros-drivers / pointgrey_camera_driver

ROS driver for Pt. Grey cameras, based on the official FlyCapture2 SDK.
128 stars 180 forks source link

2 cameras can not stream simultaneously #8

Closed dani-carbonell closed 9 years ago

dani-carbonell commented 10 years ago

Ubuntu 12.04 - ROS hydro - Camera PointGrey BFLY-PGE-13E4C-CS

I run this: roslaunch pointgrey_camera_driver camera.launch camera_serial:=14212370 roslaunch pointgrey_camera_driver camera.launch camera_serial:=13421083

Both fail with the following outputs:

The first I run----------- [camera/camera_nodelet_manager-2] process has died [pid 19061, exit code -11, cmd /opt/ros/hydro/lib/nodelet/nodelet manager name:=camera_nodelet_manager log:=/home/dardo/.ros/log/9f92dc46-17d0-11e4-9d36-448a5b417b29/camera-camera_nodelet_manager-2.log]. log file: /home/dardo/.ros/log/9f92dc46-17d0-11e4-9d36-448a5b417b29/camera-camera_nodelet_manager-2*.log [camera/camera_nodelet-3] process has finished cleanly

The second ------------

[ERROR] [1406714557.804578351]: Failed to find nodelet with name '/camera/camera_nodelet' to unload. [ERROR] [1406714558.084333320]: Failed to find nodelet with name '/camera/image_proc_debayer' to unload. [camera/camera_nodelet-2] process has finished cleanly

Then I modified the camera.launch replacing the namespace of group "camera" with an argument called "camera_name":

<launch>
  <arg name="camera_serial" default="0" />
  <arg name="camera_name" default="camera" />
  <arg name="calibrated" default="0" />
  <group ns="$(arg camera_name)">
    <node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" />

    <node pkg="nodelet" type="nodelet" name="camera_nodelet"
          args="load pointgrey_camera_driver/PointGreyCameraNodelet camera_nodelet_manager" >
      <param name="frame_id" value="camera" />
      <param name="serial" value="$(arg camera_serial)" />

      <!-- Use the camera_calibration package to create this file -->
      <param name="camera_info_url" if="$(arg calibrated)"
             value="file://$(env HOME)/.ros/camera_info/$(arg camera_serial).yaml" />
    </node>

    <node pkg="nodelet" type="nodelet" name="image_proc_debayer"
          args="load image_proc/debayer camera_nodelet_manager">
    </node>
  </group>
</launch>

I launch both cameras with different "camera_name" argument : ... camera_name:=pg1 camera_name:=pg2 and no errors. But when I run th rqt_gui with two rqt_imageview in orther to see both at the same time I get this error message in both terminals.

............. [ERROR] [1406715162.555908850]: PointGreyCamera::grabImage Failed to retrieve buffer | FlyCapture2::ErrorType 41There is an image consistency issue with this image. [ERROR] [1406715162.698881298]: PointGreyCamera::grabImage Failed to retrieve buffer | FlyCapture2::ErrorType 41There is an image consistency issue with this image. .............

mikepurvis commented 10 years ago

Let's resolve #7 before we tackle this.

dani-carbonell commented 10 years ago

After solving #7 working with 2 cameras is still impossible for me. It seems like the nodelet names are colliding. Both are the same Ethernet camera model.

mikepurvis commented 10 years ago

My suggestion would be to run a single camera_nodelet_manager, eg:

<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" />

<node pkg="nodelet" type="nodelet" name="camera_nodelet_left"
          args="load pointgrey_camera_driver/PointGreyCameraNodelet camera_nodelet_manager">
    ...
</node>
<node pkg="nodelet" type="nodelet" name="image_proc_debayer_left"
          args="load image_proc/debayer camera_nodelet_manager" />

<node pkg="nodelet" type="nodelet" name="camera_nodelet_right"
          args="load pointgrey_camera_driver/PointGreyCameraNodelet camera_nodelet_manager">
    ...
</node>
<node pkg="nodelet" type="nodelet" name="image_proc_debayer_right"
          args="load image_proc/debayer camera_nodelet_manager" />

If it works as you expect, you could use a separate launchfile with an <arg> for which camera it is, and then you'd have something more like:

<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" />
<include file="$(find my_package)/launch/camera.launch>
  <arg name="camera" value="left" />
  <arg name="serial" value="xyz" />
</include>
<include file="$(find my_package)/launch/camera.launch>
  <arg name="camera" value="right" />
  <arg name="serial" value="abc" />
</include>
dani-carbonell commented 10 years ago

I think that the problem must be with the libflycapture2:

[ERROR] [1406715162.555908850]: PointGreyCamera::grabImage Failed to retrieve buffer | FlyCapture2::ErrorType 41There is an image consistency issue with this image.

Launching two different cameras with their own group "ns" and nodelet_manager has not this problem. Running a single nodelet_manager and two nodelets with different names does not work. I still have collisions with the service names:

process[camera/camera_nodelet_manager-2]: started with pid [13338]
process[camera/camera_nodelet_right-3]: started with pid [13339]
process[camera/camera_nodelet_left-4]: started with pid [13378]
process[camera/image_proc_debayer-5]: started with pid [13399]
[ERROR] [1406739984.243625394]: Tried to advertise a service that is already advertised in this node [/camera/set_camera_info]
[ERROR] [1406739984.305534147]: Tried to advertise a service that is already advertised in this node [/camera/image_raw/compressedDepth/set_parameters]
[ERROR] [1406739984.347138730]: Tried to advertise a service that is already advertised in this node [/camera/image_raw/compressed/set_parameters]
[ERROR] [1406739984.422714555]: Tried to advertise a service that is already advertised in this node [/camera/image_raw/theora/set_parameters]
mikepurvis commented 10 years ago

Interesting.

@chadrockey Do you have any thoughts about multiple instances of libflycapture2?

chadrockey commented 10 years ago

I used it on 5 cameras at once.

Make sure each configuration is correct. You're probably opening the same camera twice.

dani-carbonell commented 10 years ago

They work separately but not at the same time. Actually they are both publishing the topics until I try to see them with two rqt_imageview.

wnoise commented 10 years ago

I have had no trouble with multiple cameras so long as the names don't collide.

wnoise commented 10 years ago

See pull request #11.

garaemon commented 10 years ago

I have similar problem when using two Flea2 USB3.0 cameras.

The first camera node can publish the images however the second one cannot publish tie images.

In my case, FlyCapture2::Camera::StartCapture() does not return on the second camera node.

the launch file is:

<launch>
  <group ns="left">
    <!-- <node pkg="nodelet" type="nodelet" args="load pointgrey_camera_driver/PointGreyCameraNodelet /manager" -->
    <!--       name="driver"> -->
    <node pkg="pointgrey_camera_driver" type="camera_node" name="driver"
          respawn="true">
      <param name="serial" value="14160044" />
    </node>
    <node pkg="image_view" type="image_view" name="image_view">
      <remap from="image" to="image_raw" />
    </node>
  </group>
  <group ns="right" if="true">
    <!-- <node pkg="nodelet" type="nodelet" args="load pointgrey_camera_driver/PointGreyCameraNodelet /manager" -->
    <!--       name="driver"> -->
    <node pkg="pointgrey_camera_driver" type="camera_node" name="driver"
          respawn="true">
      <param name="serial" value="14160053" />
    </node>
    <node pkg="image_view" type="image_view" name="image_view">
      <remap from="image" to="image_raw" />
    </node>
  </group>
  <node pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" />
</launch>
garaemon commented 10 years ago

I'm using kernel 3.11.

$ uname -a
Linux microscopium 3.11.0-26-generic #45~precise1-Ubuntu SMP Tue Jul 15 04:02:35 UTC 2014 x86_64 x86_64 x86_64 GNU/Linux
ssafarik commented 9 years ago

I have the same problem w/ two flea3 usb3 cameras, any two that I try.

First, the camera.launch needs a modification for group ns="camera_$(arg camera_serial)" (and also frame_id) as others have mentioned. That change made, then...

Second, and the main issue, is that the first camera works fine, the second does not. One manefestaion has been that StartCapture() never returns, so perhaps it's a libflycapture bug. I've also seen where it never gets as far as that call, though I haven't yet tracked down where it hangs prior.

I do have one machine where it runs successfully, but have not determined the difference w/ the nonfunctioning machines. I'm on Ubuntu 12.04, ros hydro, libflycapture 2.6.3.4 (have also tried 2.7.3.13), pointgrey_camera_driver apt-get'ted and also built from github.

My "uname -a" says "Linux uf8bc12848b5a5452582c 3.13.0-43-generic #72~precise1-Ubuntu SMP Tue Dec 9 12:14:18 UTC 2014 x86_64 x86_64 x86_64 GNU/Linux"

Can we reopen this issue?

Steve.

ssafarik commented 9 years ago

It looks like it was related to the /etc/default/grub param "usbcore.usbfs_memory_mb=1000". Making extra sure that the setting is correct, running "sudo update-grub", running "sudo modprobe usbcore usbfs_memory_mb=1000", and rebooting, etc, gets it to work.

dani-carbonell commented 9 years ago

In my case, I use two Blackfly ethernet cameras, so I guess this solution does not help me. Any idea?

PatrickHussey commented 9 years ago

configuration Intense PC Pro Barebones; 512GB SSD; 16GB RAM; 2x Flea3 USB3 (FL3-U3-13E4C); Ubuntu 12.04 LTS (3.5.0-51-generic); ROS Hydro; latest version of point_grey_camera_driver

what ssafarik suggested worked for me as well follow section 1.10 in the following document

http://www.ptgrey.com/Content/Images/Uploaded/Downloads/Firmware/2014/TAN2012007_UsingLinuxUSB3.pdf?

here is the launch:

<launch>
  <arg name="left_camera_serial" default="14092850" />
  <arg name="left_camera_calibrated" default="0" />
  <arg name="right_camera_serial" default="14092848" />
  <arg name="right_camera_calibrated" default="0" />
  <arg name="frame_rate" default="15" />

<group ns="left_camera">
    <node pkg="nodelet" type="nodelet" name="left_camera_nodelet_manager" args="manager" />

    <node pkg="nodelet" type="nodelet" name="left_camera_nodelet"
          args="load pointgrey_camera_driver/PointGreyCameraNodelet left_camera_nodelet_manager" >
      <param name="frame_id" value="left_camera" />
      <param name="serial" value="$(arg left_camera_serial)" />

      <!-- When unspecified, the driver will use the default framerate as given by the
           camera itself. Use this parameter to override that value for cameras capable of
           other framerates. -->
      <param name="frame_rate" value="$(arg frame_rate)" />

      <!-- Use the camera_calibration package to create this file -->
      <param name="camera_info_url" if="$(arg left_camera_calibrated)"
             value="file://$(env HOME)/.ros/camera_info/$(arg left_camera_serial).yaml" />
    </node>

    <node pkg="nodelet" type="nodelet" name="image_proc_debayer_left"
        args="load image_proc/debayer left_camera_nodelet_manager">
    </node>
  </group>

  <group ns="right_camera">
    <node pkg="nodelet" type="nodelet" name="right_camera_nodelet_manager" args="manager" />

    <node pkg="nodelet" type="nodelet" name="right_camera_nodelet"
          args="load pointgrey_camera_driver/PointGreyCameraNodelet right_camera_nodelet_manager" >
      <param name="frame_id" value="right_camera" />
      <param name="serial" value="$(arg right_camera_serial)" />

      <!-- When unspecified, the driver will use the default framerate as given by the
           camera itself. Use this parameter to override that value for cameras capable of
           other framerates. -->
      <param name="frame_rate" value="$(arg frame_rate)" />

      <!-- Use the camera_calibration package to create this file -->
      <param name="camera_info_url" if="$(arg right_camera_calibrated)"
             value="file://$(env HOME)/.ros/camera_info/$(arg right_camera_serial).yaml" />
    </node>

    <node pkg="nodelet" type="nodelet" name="image_proc_debayer_right"
        args="load image_proc/debayer right_camera_nodelet_manager">
    </node>
  </group>
</launch>

THANKS!

PatrickHussey commented 9 years ago

Hey dani-carbonell, you might also be experiencing memory buffer issues. We had to tune the OS settings to get the bandwidth we required for distributed processing and multiple vision systems (CRL Multisense SL, 2x Flea3 USB3, and 2x IPC pro (for vision and nav)). Assuming you have a Gig NIC, try setting your UDP buffers higher than the defaults for the OS. For UDP rmem_max and wmem_max GigE settings try:

echo 16777215 > /proc/sys/net/core/rmem_max
echo 16777215 > /proc/sys/net/core/wmem_max

if it works go into /etc/sysctl.conf and add this to make it permanent:

net.core.rmem_max = 16777215 
net.core.wmem_max = 16777215 
mikepurvis commented 9 years ago

This is fantastic, thanks for looking into it @ssafarik and @SISegwayRmp. If someone could take a few minutes to transcribe the relevant details to the ROS Wiki, I'd really appreciate it.

Are we clear to re-close the ticket?

ssafarik commented 9 years ago

You can close it as far as I'm concerned.

Steve.

On Sun, Jan 18, 2015 at 8:15 PM, Mike Purvis notifications@github.com wrote:

This is fantastic, thanks for looking into it @ssafarik https://github.com/ssafarik and @SISegwayRmp https://github.com/SISegwayRmp. If someone could take a few minutes to transcribe the relevant details to the ROS Wiki http://wiki.ros.org/pointgrey_camera_driver#Troubleshooting, I'd really appreciate it.

Are we clear to re-close the ticket?

— Reply to this email directly or view it on GitHub https://github.com/ros-drivers/pointgrey_camera_driver/issues/8#issuecomment-70444615 .

mikepurvis commented 9 years ago

Okay, thanks again.

PatrickHussey commented 9 years ago

Same here I have done a bunch of testing also closed the other bug I opened which was directly related