ROS:Object Detection

From OpenRAVE
Revision as of 08:08, 18 April 2011 by Rdiankov (Talk | contribs) (Created page with "= Object Detection with ROS/OpenRAVE = "posedetection_msgs", which decides the connection message, is the central role here. Each feature and obj...")

(diff) ← Older revision | Latest revision (diff) | Newer revision → (diff)
Jump to: navigation, search

Object Detection with ROS/OpenRAVE

"posedetection_msgs", which decides the connection message, is the central role here. Each feature and object-detection module use this message, and therefore they can cooperate with one another.

Message F

Curve1D
Feature0D
Feature1D
ImageFeature0D
ImageFeature1D
Object6DPose - One detected object
ObjectDetection - Object detection output

Service F

Detect
Feature0DDetect
Feature1DDetect

Features are separated between 0-dimensional "point" and 1-dimensional "line".

The package required to compute features according to this message is

imagesift

The package required to output the result of the object according to this message is

checkerboard_detector
posedetectiondb

Posture-and-orientation detection of textured planes

Let's boot up the easy program on plane detection based on PointPoseExtraction.py script in posedetectiondb

rosmake --rosdep-install posedetectiondb 

Quick start

To start feature extraction F rosrun imagesift imagesift

To start detection module rosrun posedetectiondb PointPoseExtraction.py

Choose 4 points by left click on the mouse, and create template.pp file. This texture is used to be searched from images.

To see the image in pp file, run the following script

python -c "import scipy, pickle; scipy.misc.pilutil.imshow(pickle.load(open(raw_input('enter filename: '),'r'))['Itemplate'])"

Execution example using IEEE1394Camera(FLEA)

Open camera F The example of roslaunch file is as follows <source lang="xml"> <launch>

 <group ns="FLEA">
   <param name="display" type="int" value="0"/>
   <param name="mode" value="MODE_640x480_MONO8"/>
   <param name="framerate" type="double" value="15"/>
   <param name="colorfilter" type="string" value="COLOR_FILTER_GBRG"/>
   <param name="compression" type="string" value="raw"/>
   <param name="frame_id" type="string" value="left_base"/>
   <param name="KK_fx" type="double" value="493.336823"/>
   <param name="KK_fy" type="double" value="493.239960"/>
   <param name="KK_cx" type="double" value="308.050354"/>
   <param name="KK_cy" type="double" value="242.917526"/>
   <param name="kc_k1" type="double" value="-0.342432"/>
   <param name="kc_k2" type="double" value="0.123768"/>
   <param name="kc_p1" type="double" value="-0.000268"/>
   <param name="kc_p2" type="double" value="0.000052"/>
   <node name="cam" pkg="cameradc1394" type="cameradc1394" respawn="true" output="screen">
   </node>
   <node name="iview" pkg="image_view" type="image_view">
   </node>
 </group>

</launch> </source>

sudo chown user:group /dev/raw1394
roslaunch cameradc.ros.xml 

The explanation of calib is in http://openrave.programmingvision.com/index.php/Working_with_Cameras


Start feature extraction F

ROS_NAMESPACE=FLEA rosrun imagesift imagesift

Of course it is also possible to roslaunch as follows <source lang="xml"> <launch> <group ns="FLEA">

   <node name="sift" pkg="imagesift" type="imagesift" output="screen"/>

</group> </launch> </source>


Start detection module and create template.pp F

ROS_NAMESPACE=FLEA rosrun posedetectiondb PointPoseExtraction.py

Click the four corners of the detection-target texture one by one.

300px 300px 300px 300px

The vector from the first point to the second point becomes the positive sense of x-axis.

In the current specification, to click points clockwise is expected.


(The above image was captured before bug fixing. I will replace it by a new one someday.)


When you finish clicking the fourth point, you will be asked to input the width and height on the terminal. Input them in the order of "width height", by meters.

(For example, input "0.13 0.14" if the size is 13cmx14cm.)

If it is suceeded, the following window appears

300px

P.S.: Fatal bug, which brought a mirror plane as above, was fixed on 5/3. The detection accuracy increased dramatically. I will replace the above image by a new one someday.


Detection test F The example of roslaunch file is as follows <source lang="xml"> <launch> <group ns="FLEA">

 <node name="template" pkg="posedetectiondb"
 type="PointPoseExtraction.py" args="--errorthresh=0.007
 --neighthresh=0.8 --dminexpected=10 --ransaciters=200
 --template=/hoge/template.pp" output="screen"/>

</group> </launch> </source> The parameters are only an example.

Running camera and imagesift, roslaunch this

roslaunch template.ros.xml

The success examples are as follows

300px 300px

Explanation of parameters

rosrun posedetectiondb PointPoseExtraction.py --help

When you run this script, you can see the explanation of each parameter.

Connection to OpenRAVE Objects