Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[jsk_perception/mask_image_to_rect.cpp] check indices size before execute boundingRect #2113

Merged
merged 3 commits into from
Jun 22, 2017

Conversation

kochigami
Copy link
Contributor

When I execute the launch below (1) inside the robot, the error message (2) appeared.
However, it worked well with my PC.
I found the error occurred because the list of indices is empty by print debug (3).
It seems that this difference occurred because the process inside robot is slower than local PC (4).

That's why I added the line of checking indices size.
If there is any problem, please let me know.

(1) launch I wrote (I referenced jsk_perception/sample_flow_velocity_thresholding.launch)
(I modified INPUT_IMAGE and deleted rosbag_play node when executing it with robot)

<launch>

  <arg name="gui" default="true" />

  <param name="/use_sim_time" value="true" />
  <node name="rosbag_play"
        pkg="rosbag" type="play"
        args="$(find jsk_perception)/sample/data/2016-10-15-23-21-42_moving_bottle.bag --clock"
        required="true">
  </node>

  <arg name="INPUT_IMAGE" value="/camera/rgb/image_rect_color" />

  <node name="fback_flow"
        pkg="opencv_apps" type="fback_flow">
    <remap from="image" to="$(arg INPUT_IMAGE)" />
    <rosparam>
      use_camera_info: false
    </rosparam>
  </node>

  <node name="flow_velocity_thresholding"
        pkg="jsk_perception" type="flow_velocity_thresholding">
    <remap from="~input/flows" to="fback_flow/flows" />
    <rosparam>
      approximate_sync: false
      use_camera_info: false
      image_height: 480
      image_width: 640
      window_size: 16
      threshold: 5.0
    </rosparam>
  </node>

  <node name="mask_image_to_rect"
        pkg="jsk_perception" type="mask_image_to_rect" output="screen">
    <remap from="~input" to="flow_velocity_thresholding/output" />
  </node>

  <node name="apply_mask_image"
        pkg="jsk_perception" type="apply_mask_image">
    <remap from="~input" to="$(arg INPUT_IMAGE)" />
    <remap from="~input/mask" to="flow_velocity_thresholding/output" />
    <rosparam>
      clip: false
    </rosparam>
  </node>

  <node name="draw_rect_array"
	pkg="jsk_perception" type="draw_rect_array.py">
    <remap from="~input" to="$(arg INPUT_IMAGE)" />
    <remap from="~input/polygon" to="mask_image_to_rect/output" />
  </node>

</launch>

(2) error of roslaunch test.launch + then executing rostopic echo /mask_image_to_rect/output

OpenCV Error: Assertion failed (points.checkVector(2) >= 0 && (points.depth() == CV_32F || points.depth() == CV_32S)) in boundingRect, file /build/buildd/opencv-2.4.8+dfsg1/modules/imgproc/src/contours.cpp, line 1895
terminate called after throwing an instance of 'cv::Exception'
  what():  /build/buildd/opencv-2.4.8+dfsg1/modules/imgproc/src/contours.cpp:1895: error: (-215) points.checkVector(2) >= 0 && (points.depth() == CV_32F || points.depth() == CV_32S) in function boundingRect

(3) print debug
I added std::cout << indices << std::endl; before https://github.com/jsk-ros-pkg/jsk_recognition/blob/master/jsk_perception/src/mask_image_to_rect.cpp#L79
like

    std::cout << indices << std::endl;
    cv::Rect mask_rect = cv::boundingRect(indices);

the output of std::cout << indices << std::endl; is []
when the error (2) occurred.

(4) rostopic hz

inside robot

subscribed to [/mask_image_to_rect/output]
average rate: 1.321
        min: 0.012s max: 1.502s std dev: 0.74497s window: 3
average rate: 1.660
        min: 0.005s max: 1.502s std dev: 0.63208s window: 5
no new messages
average rate: 1.728
        min: 0.005s max: 1.502s std dev: 0.61308s window: 9
average rate: 1.736
        min: 0.005s max: 1.502s std dev: 0.57806s window: 10
average rate: 1.825
        min: 0.005s max: 1.502s std dev: 0.52785s window: 13
average rate: 1.932
        min: 0.005s max: 1.502s std dev: 0.50944s window: 15
no new messages
no new messages
no new messages
average rate: 1.391
        min: 0.005s max: 4.106s std dev: 0.99992s window: 17
average rate: 1.489
        min: 0.005s max: 4.106s std dev: 0.95672s window: 19
no new messages
average rate: 1.369
        min: 0.005s max: 4.106s std dev: 0.99020s window: 21

my PC

/mask_image_to_rect/output 
subscribed to [/mask_image_to_rect/output]
WARNING: may be using simulated time
average rate: 8.209
	min: 0.111s max: 0.141s std dev: 0.00929s window: 8
average rate: 7.844
	min: 0.111s max: 0.161s std dev: 0.01465s window: 16
average rate: 7.609
	min: 0.111s max: 0.161s std dev: 0.01504s window: 23
average rate: 7.727
	min: 0.111s max: 0.161s std dev: 0.01521s window: 31
average rate: 7.611
	min: 0.111s max: 0.161s std dev: 0.01617s window: 38
average rate: 7.616
	min: 0.111s max: 0.161s std dev: 0.01598s window: 45
average rate: 7.589
	min: 0.111s max: 0.161s std dev: 0.01571s window: 52
average rate: 7.515
	min: 0.111s max: 0.252s std dev: 0.02206s window: 60
average rate: 7.486
	min: 0.111s max: 0.252s std dev: 0.02168s window: 64

@kochigami kochigami changed the title [jsk_perception] check indices size before execute boundingRect [jsk_perception/mask_image_to_rect.cpp] check indices size before execute boundingRect Jun 13, 2017
rect.polygon.points.push_back(min_pt);
rect.polygon.points.push_back(max_pt);
pub_.publish(rect);
if (indices.size() > 0){
Copy link
Member

@furushchev furushchev Jun 13, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just a comment. I think it'd be better to publish empty message (only with timestamp) even when no region is masked on input image.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you very much for your comment.
I modified it.

@kochigami
Copy link
Contributor Author

Could you merge this when you have time?

@k-okada k-okada merged commit c5e3071 into jsk-ros-pkg:master Jun 22, 2017
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants