vision_detect_plug

vision_detect_plug action is used to detect the pose of a plug in a gripper.

Action Goal

vision_detect_plug/goal (pr2_plugs_msgs/VisionPlugDetectionGoal)
  • The goal gives the camera to use, a prior pose of an outlet and a wall norm.

Action Result

vision_detect_plug/result (pr2_plugs_msgs/VisionPlugDetectionResult)
  • This returns the pose of the outlet.

Subscribed Topics

<camera_name>/image_rect (sensor_msgs/Image)
  • This subscribes to the image from the camera.

Published Topics

~display_image (sensor_msgs/Image)
  • Camera image marked with detected checkerboard corners.

Parameters

Checkerboard dimensions

The checkerboard detector looks for the interior corners; for example, a standard checkerboard is considered to have dimensions 7x7.
~board_width (int)
  • The number of interior corners in the horizontal direction.
~board_height (int)
  • The number of interior corners in the vertical direction.
~square_size (double)
  • The length of a checkerboard square edge (meters).

Detection options

~subpixel_corners (bool, default: true)
  • Whether to perform subpixel refinement on detected corners. This usually yields a more accurate pose.

Checkerboard to plug transform

plug_position_* is the position of the plug frame origin in the checkerboard frame. plug_orientation_* is a quaternion rotating the plug frame to the checkerboard frame. With the plug positioned for entering the outlet, the checkerboard frame is:
  • Origin: The lower-right interior checkerboard corner.
  • X: Down
  • Y: Forward (towards the outlet)
  • Z: Into the plug
(diagrams needed)
~plug_position_x (double)
  • X coordinate.
~plug_position_y (double)
  • Y coordinate.
~plug_position_z (double)
  • Z coordinate.
~plug_orientation_x (double)
  • Quaternion X.
~plug_orientation_y (double)
  • Quaternion Y.
~plug_orientation_z (double)
  • Quaternion Z.
~plug_orientation_w (double)
  • Quaternion W.

Wiki: pr2_plugs_actions/vision_detect_plug_action (last edited 2010-03-02 05:05:58 by PatrickMihelich)