ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

camera_1394 nodelet speed issues on Gumstix

asked 2011-10-26 15:01:49 -0500

Bradley Powers gravatar image

updated 2014-01-28 17:10:39 -0500

ngrennan gravatar image

Hello all,

The battle of getting images processed on a Gumstix continues (see This Question for getting OpenCV running efficiently on Gumstix). As I've gotten in to monitoring more closely what is going on with my code, I'm noticing that the camera_1394 nodelet is taking up a significant amount of processor time (on the order of 60%-70%). Further, I've stripped down the nodelet to only perform image debayering in hopes of minimizing the amount of processing performed, but this seems to accomplish little in terms of reducing processor load. I was hoping that someone might be able to shed some light on why this little nodelet is such a processor hog, and what I might do in order to reduce the amount of CPU time it takes up. For reference, here is my launch file:

<launch>

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

  <!-- camera driver nodelet -->
  <node pkg="nodelet" type="nodelet" name="camera1394_nodelet"
        args="load camera1394/driver camera_nodelet_manager">
        <rosparam file="$(find omnisensor)/params/ffmv.yaml" />
  </node>

  <!-- Bayer color decoding -->
  <node pkg="nodelet" type="nodelet" name="image_proc_debayer"
        args="load image_proc/debayer camera_nodelet_manager">
    <param name="bayer_pattern" value="rggb" />
    <param name="bayer_method" value="" />
    <remap from="image_color" to="camera/image_color" />
    <remap from="image_mono" to="camera/image_mono" />
    <remap from="image_raw" to="camera/image_raw" />
  </node>

  <node pkg="image_view" type="image_view" name="image_view" >
    <remap from="image" to="camera/image_color"/>
  </node>

  <node pkg="omnisensor" type="find_laser_filtered.py" name="laser_filter" />

  <node pkg="image_view" type="image_view"  name="laser_filter_view" >
    <remap from="image" to="laser_image"/>
  </node>

</launch>

Just to clarify what's going on here, the find_laser_filtered.py is the code I'm running for my application, and the image_views are for debugging purposes. Both image_view nodes die on launch, I keep them there so I can run the same launch file on my dev machine and the robot.

Anyway, any ideas you might have to reduce the CPU load caused by the camera1394 nodelet would be much appreciated.

Thanks, Bradley Powers


Update

Here's my ffmv.yaml file, as called by the camera driver nodelet.

{auto_brightness: 2, auto_exposure: 2, auto_focus: 5, auto_gain: 2, auto_gamma: 0,
  auto_hue: 5, auto_iris: 5, auto_saturation: 5, auto_sharpness: 5, auto_shutter: 2,
  auto_white_balance: 3, auto_zoom: 5, bayer_method: '', bayer_pattern: rggb, binning_x: 0,
  binning_y: 0, brightness: 138.0, camera_info_url: '', exposure: 0.0, focus: 0.0,
  format7_color_coding: mono8, format7_packet_size: 0, frame_id: /camera, frame_rate: 60.0,
  gain: 12.041193008422852, gamma: 1.2000000000000002, guid: 00b09d0100a80b41, hue: 0.0,
  iris: 8.0, iso_speed: 400, reset_on_open: false, roi_height: 0, roi_width: 0, saturation: 1.0,
  sharpness: 1.0, shutter: 0.066243231296539307, use_ros_time: true, video_mode: 640x480_mono8,
  white_balance_BU: 512.0, white_balance_RV: 512.0, x_offset: 0, y_offset: 0, zoom: 0.0}

The file was auto generated through dynamic_reconfigure.


Update

I was mistaken! The nodelet taking up all of the processing time isn't the camera1394_nodelet (1% CPU utilization), it's the camera_nodelet_manager (37% utilization)!

Why on earth is the manager requiring sooo much CPU? If I'm understanding correctly, it's simply there to monitor for crashes...

edit retag flag offensive close merge delete

Comments

What are you using to determine camera_nodelet_manager CPU utilization?
Asomerville gravatar image Asomerville  ( 2011-10-27 06:32:32 -0500 )edit
top, and tracking pid based on rosnode info
Bradley Powers gravatar image Bradley Powers  ( 2011-10-27 12:04:27 -0500 )edit
You might try "top -H" to show all threads.
joq gravatar image joq  ( 2011-10-28 03:12:45 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2011-10-27 05:08:55 -0500

Bradley Powers gravatar image

updated 2011-10-27 06:17:41 -0500

When I run the camera1394_nodelet and camera_nodelet_manager without the image_proc_debayer nodelet, it only takes up approximately 1% of CPU time. The manager nodelet takes up ,pre than 37%. I'm using this launch file:

<launch>

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

  <!-- camera driver nodelet -->
  <node pkg="nodelet" type="nodelet" name="camera1394_nodelet"
        args="load camera1394/driver camera_nodelet_manager">
        <rosparam file="$(find omnisensor)/params/ffmv.yaml" />
  </node>
</launch>

What gives here? Why is the manager taking so long? Should I switch to running everything within the node? If so, is it possible to get image debayering happening within the node, or do I need to rely on running a seperate image_proc?

edit flag offensive delete link more

Comments

This isn't an answer. It should probably be deleted and simply integrated into your original question.
Asomerville gravatar image Asomerville  ( 2011-10-27 06:29:36 -0500 )edit
1

answered 2011-10-27 02:04:41 -0500

joq gravatar image

updated 2011-10-27 03:36:07 -0500

Bayer decoding can have a noticeable effect on the CPU usage of the camera1394 driver. Doing it in a separate nodelet thread is generally a good idea. The de-Bayer cycles still occur, but they can take advantage of multiple CPUs (if any), and will not delay capturing new frames in the driver.

Looking at your launch file, you passed

<param name="bayer_pattern" value="rggb" />
<param name="bayer_method" value="" />

to image_proc/debayer. That looks wrong. You probably want to pass those values to camera1394/driver, not image_proc. They should cause the driver not to de-Bayer in its own thread.

I cannot tell what parameters are defined by "$(find omnisensor)/params/ffmv.yaml". If you still have problems, perhaps you should add them to your question, as well.

Update

I see you are already passing those same parameters to the driver. Passing them to image_proc should have no effect, so parameter confusion is the not the cause of this problem.

There should not be any heavy processing in the driver thread. It does have to allocate an Image message and copy the data there (for publishing shared_ptr to other nodelets). The rest of that thread is mainly libdc1394.

Are you able to distinguish overhead in the camera_nodelet_manager process by thread? If the driver thread uses 60-70%, what about the image_proc thread?

As an experiment, what happens if you don't run image_proc? Can you see Bayer-encoded black and white images on /camera/image_raw? Does that reduce the overhead significantly?

edit flag offensive delete link more

Comments

Sounds like you are measuring CPU usage per-process. The `camera_nodelet_manager` runs *all* the nodelet threads. The `camera1394_nodelet` process merely loads the nodelet into `camera_nodelet_manager`, then waits for it to finish.
joq gravatar image joq  ( 2011-10-27 07:57:48 -0500 )edit
The manager process actually does all the of the work. It seems that Bayer decoding costs a significant number of cycles on your Gumstix.
joq gravatar image joq  ( 2011-10-28 03:18:28 -0500 )edit

Question Tools

Stats

Asked: 2011-10-26 15:01:49 -0500

Seen: 499 times

Last updated: Oct 27 '11