|
From: <mar...@us...> - 2009-04-02 18:44:15
|
Revision: 13319
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=13319&view=rev
Author: mariusmuja
Date: 2009-04-02 18:44:12 +0000 (Thu, 02 Apr 2009)
Log Message:
-----------
Moved door_handle_detect (vision door handle detection) into the door_handle_detection node.
Modified Paths:
--------------
pkg/trunk/mapping/door_handle_detector/CMakeLists.txt
pkg/trunk/mapping/door_handle_detector/manifest.xml
Added Paths:
-----------
pkg/trunk/mapping/door_handle_detector/launch/handle_detector_vision.launch
pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp
Removed Paths:
-------------
pkg/trunk/vision/door_handle_detect/CMakeLists.txt
pkg/trunk/vision/door_handle_detect/Makefile
pkg/trunk/vision/door_handle_detect/data/annotate.py
pkg/trunk/vision/door_handle_detect/data/convert.py
pkg/trunk/vision/door_handle_detect/data/handles_data.xml
pkg/trunk/vision/door_handle_detect/handles.launch
pkg/trunk/vision/door_handle_detect/manifest.xml
pkg/trunk/vision/door_handle_detect/src/door_handle_detect.cpp
pkg/trunk/vision/door_handle_detect/src/test.cpp
Modified: pkg/trunk/mapping/door_handle_detector/CMakeLists.txt
===================================================================
--- pkg/trunk/mapping/door_handle_detector/CMakeLists.txt 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/mapping/door_handle_detector/CMakeLists.txt 2009-04-02 18:44:12 UTC (rev 13319)
@@ -42,6 +42,7 @@
rospack_add_library(executive_functions src/executive_functions.cpp)
+rospack_add_executable(handle_detector_vision src/handle_detector_vision.cpp)
Copied: pkg/trunk/mapping/door_handle_detector/launch/handle_detector_vision.launch (from rev 13318, pkg/trunk/vision/door_handle_detect/handles.launch)
===================================================================
--- pkg/trunk/mapping/door_handle_detector/launch/handle_detector_vision.launch (rev 0)
+++ pkg/trunk/mapping/door_handle_detector/launch/handle_detector_vision.launch 2009-04-02 18:44:12 UTC (rev 13319)
@@ -0,0 +1,31 @@
+
+<launch>
+ <!-- videre_mode should be one of the following:
+ disparity: Disparity and rectification done on chip.
+ Provides: Disparity and left mono image
+ disparity_raw: Disparity done on chip (debayer and rectification in software).
+ Provides: disparity and left color image.
+ none: No stereo on chip (all processing done in software).
+ Provides: all 3 images available
+ rectified: Rectification on chip
+ Provides: all 3 images available but no color
+ -->
+ <param name="stereo/videre_mode" type="str" value="none"/>
+ <param name="stereo/do_colorize" type="bool" value="True"/>
+ <param name="stereo/do_rectify" type="bool" value="True"/>
+ <param name="stereo/do_stereo" type="bool" value="True"/>
+ <param name="stereo/do_calc_points" type="bool" value="True"/>
+ <param name="stereo/do_keep_coords" type="bool" value="True"/>
+ <param name="stereo/horopter" value="128"/>
+ <param name="stereo/ndisp" value="128"/>
+ <param name="stereo/gain" type="int" value="10"/>
+ <param name="stereo/exposure" type="int" value="100"/>
+
+
+<!-- <node pkg="dcam" type="stereodcam" respawn="false"/>-->
+ <node pkg="stereo_image_proc" type="stereoproc" respawn="false"/>
+ <node pkg="door_handle_detector" name="handle_detector_vision" type="handle_detector_vision" respawn="false" output="screen">
+ <param name="display" type="bool" value="true" />
+ </node>
+</launch>
+
Modified: pkg/trunk/mapping/door_handle_detector/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_handle_detector/manifest.xml 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/mapping/door_handle_detector/manifest.xml 2009-04-02 18:44:12 UTC (rev 13319)
@@ -20,6 +20,11 @@
<depend package="point_cloud_assembler" />
<depend package="std_msgs" />
<depend package="sbpl_arm_executive" />
+ <depend package="opencv_latest"/>
+ <depend package="image_msgs"/>
+ <depend package="topic_synchronizer"/>
+ <depend package="stereo_utils"/>
+ <depend package="tf"/>
<export>
Copied: pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp (from rev 13318, pkg/trunk/vision/door_handle_detect/src/door_handle_detect.cpp)
===================================================================
--- pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp (rev 0)
+++ pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-04-02 18:44:12 UTC (rev 13319)
@@ -0,0 +1,989 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+// Author: Marius Muja
+
+#include <vector>
+#include <fstream>
+#include <sstream>
+#include <time.h>
+#include <iostream>
+#include <iomanip>
+
+
+#include "image_msgs/CvBridge.h"
+
+#include "opencv/cxcore.h"
+#include "opencv/cv.h"
+#include "opencv/highgui.h"
+
+#include "ros/node.h"
+#include "image_msgs/StereoInfo.h"
+#include "image_msgs/DisparityInfo.h"
+#include "image_msgs/CamInfo.h"
+#include "image_msgs/Image.h"
+#include "robot_msgs/PointCloud.h"
+#include "robot_msgs/Point32.h"
+#include "robot_msgs/PointStamped.h"
+#include "robot_msgs/Door.h"
+#include "robot_msgs/VisualizationMarker.h"
+#include "door_handle_detector/DoorsDetector.h"
+
+#include <string>
+
+// transform library
+#include <tf/transform_listener.h>
+
+#include "topic_synchronizer.h"
+
+#include "CvStereoCamModel.h"
+
+#include <boost/thread.hpp>
+
+using namespace std;
+
+template <typename T>
+class IndexedIplImage
+{
+public:
+ IplImage* img_;
+ T* p;
+
+ IndexedIplImage(IplImage* img) : img_(img)
+ {
+ p = (T*)img_->imageData;
+ }
+
+ operator IplImage*()
+ {
+ return img_;
+ }
+
+ T at(int x, int y, int chan = 0)
+ {
+ return *(p+y*img_->width+x*img_->nChannels+chan);
+ }
+
+ T integral_sum(const CvRect &r)
+ {
+ return at(r.x+r.width+1,r.y+r.height+1)-at(r.x+r.width+1,r.y)-at(r.x,r.y+r.height+1)+at(r.x,r.y);
+ }
+
+};
+
+class HandleDetector : public ros::Node
+{
+public:
+
+
+ image_msgs::Image limage;
+ image_msgs::Image rimage;
+ image_msgs::Image dimage;
+ image_msgs::StereoInfo stinfo;
+ image_msgs::DisparityInfo dispinfo;
+ image_msgs::CamInfo rcinfo;
+ image_msgs::CvBridge lbridge;
+ image_msgs::CvBridge rbridge;
+ image_msgs::CvBridge dbridge;
+
+ robot_msgs::PointCloud cloud_fetch;
+ robot_msgs::PointCloud cloud;
+
+ IplImage* left;
+ IplImage* right;
+ IplImage* disp;
+ IplImage* disp_clone;
+
+ TopicSynchronizer<HandleDetector> sync;
+
+ boost::mutex cv_mutex;
+ boost::condition_variable images_ready;
+
+ tf::TransformListener *tf_;
+
+
+ // minimum height to look at (in base_link frame)
+ double min_height;
+ // maximum height to look at (in base_link frame)
+ double max_height;
+ // no. of frames to detect handle in
+ int frames_no;
+ // display stereo images ?
+ bool display;
+
+
+
+ CvHaarClassifierCascade* cascade;
+ CvMemStorage* storage;
+
+ HandleDetector()
+ :ros::Node("stereo_view"), left(NULL), right(NULL), disp(NULL), disp_clone(NULL), sync(this, &HandleDetector::image_cb_all, ros::Duration().fromSec(0.1), &HandleDetector::image_cb_timeout)
+ {
+ tf_ = new tf::TransformListener(*this);
+ // define node parameters
+
+
+ param("~min_height", min_height, 0.7);
+ param("~max_height", max_height, 1.0);
+ param("~frames_no", frames_no, 7);
+
+
+ param("~display", display, false);
+ stringstream ss;
+ ss << getenv("ROS_ROOT") << "/../ros-pkg/vision/door_handle_detect/data/";
+ string path = ss.str();
+ string cascade_classifier;
+ param<string>("cascade_classifier", cascade_classifier, path + "handles_data.xml");
+
+ if(display){
+ cvNamedWindow("left", CV_WINDOW_AUTOSIZE);
+ //cvNamedWindow("right", CV_WINDOW_AUTOSIZE);
+ cvNamedWindow("disparity", CV_WINDOW_AUTOSIZE);
+ cvNamedWindow("disparity_original", CV_WINDOW_AUTOSIZE);
+ }
+
+// subscribeStereoData();
+
+ // load a cascade classifier
+ loadClassifier(cascade_classifier);
+ // invalid location until we get a detection
+
+// advertise<robot_msgs::PointStamped>("handle_detector/handle_location", 1);
+ advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 1);
+ advertiseService("door_handle_vision_detector", &HandleDetector::detectHandleSrv, this);
+ }
+
+ ~HandleDetector()
+ {
+ if(left){
+ cvReleaseImage(&left);
+ }
+ if(right){
+ cvReleaseImage(&right);
+ }
+ if(disp){
+ cvReleaseImage(&disp);
+ }
+ if(storage){
+ cvReleaseMemStorage(&storage);
+ }
+ }
+
+private:
+ void loadClassifier(string cascade_classifier)
+ {
+ // subscribe("/door_detector/door_msg", door, &HandleDetector::door_detected,1);
+ ROS_INFO("Loading cascade classifier");
+ cascade = (CvHaarClassifierCascade*)(cvLoad(cascade_classifier.c_str(), 0, 0, 0));
+ if(!cascade){
+ ROS_ERROR("Cannot load cascade classifier\n");
+ }
+ storage = cvCreateMemStorage(0);
+ }
+
+ void subscribeStereoData()
+ {
+
+ sync.reset();
+ std::list<std::string> left_list;
+ left_list.push_back(std::string("stereo/left/image_rect_color"));
+ left_list.push_back(std::string("stereo/left/image_rect"));
+ sync.subscribe(left_list, limage, 1);
+
+ // std::list<std::string> right_list;
+ // right_list.push_back(std::string("stereo/right/image_rect_color"));
+ // right_list.push_back(std::string("stereo/right/image_rect"));
+ // sync.subscribe(right_list, rimage, 1);
+
+ sync.subscribe("stereo/disparity", dimage, 1);
+ sync.subscribe("stereo/stereo_info", stinfo, 1);
+ sync.subscribe("stereo/disparity_info", dispinfo, 1);
+ sync.subscribe("stereo/right/cam_info", rcinfo, 1);
+ sync.subscribe("stereo/cloud", cloud_fetch, 1);
+ sync.ready();
+// sleep(1);
+ }
+
+ void unsubscribeStereoData()
+ {
+// unsubscribe("stereo/left/image_rect_color");
+ unsubscribe("stereo/left/image_rect");
+ unsubscribe("stereo/disparity");
+ unsubscribe("stereo/stereo_info");
+ unsubscribe("stereo/disparity_info");
+ unsubscribe("stereo/right/cam_info");
+ unsubscribe("stereo/cloud");
+ }
+
+ /////////////////////////////////////////////////
+ // Analyze the disparity image that values should not be too far off from one another
+ // Id -- 8 bit, 1 channel disparity image
+ // R -- rectangular region of interest
+ // vertical -- This is a return that tells whether something is on a wall (descending disparities) or not.
+ // minDisparity -- disregard disparities less than this
+ //
+ double disparitySTD(IplImage *Id, const CvRect & R, double & meanDisparity, double minDisparity = 0.5)
+ {
+ int ws = Id->widthStep;
+ unsigned char *p = (unsigned char*)(Id->imageData);
+ int rx = R.x;
+ int ry = R.y;
+ int rw = R.width;
+ int rh = R.height;
+ int nchan = Id->nChannels;
+ p += ws * ry + rx * nchan; //Put at start of box
+ double mean = 0.0, var = 0.0;
+ double val;
+ int cnt = 0;
+ //For vertical objects, Disparities should decrease from top to bottom, measure that
+ for(int Y = 0;Y < rh;++Y){
+ for(int X = 0;X < rw;X++, p += nchan){
+ val = (double)*p;
+ if(val < minDisparity)
+ continue;
+
+ mean += val;
+ var += val * val;
+ cnt++;
+ }
+ p += ws - (rw * nchan);
+ }
+
+ if(cnt == 0){
+ return 10000000.0;
+ }
+ //DO THE VARIANCE MATH
+ mean = mean / (double)cnt;
+ var = (var / (double)cnt) - mean * mean;
+ meanDisparity = mean;
+ return (sqrt(var));
+ }
+
+ /**
+ * \brief Transforms a disparity image pixel to real-world point
+ *
+ * @param cam_model Camera model
+ * @param x coordinate in the disparity image
+ * @param y coordinate in the disparity image
+ * @param d disparity pixel value
+ * @return point in 3D space
+ */
+ robot_msgs::Point disparityTo3D(CvStereoCamModel & cam_model, int x, int y, double d)
+ {
+ CvMat *uvd = cvCreateMat(1, 3, CV_32FC1);
+ cvmSet(uvd, 0, 0, x);
+ cvmSet(uvd, 0, 1, y);
+ cvmSet(uvd, 0, 2, d);
+ CvMat *xyz = cvCreateMat(1, 3, CV_32FC1);
+ cam_model.dispToCart(uvd, xyz);
+ robot_msgs::Point result;
+ result.x = cvmGet(xyz, 0, 0);
+ result.y = cvmGet(xyz, 0, 1);
+ result.z = cvmGet(xyz, 0, 2);
+ return result;
+ }
+
+ /**
+ * \brief Computes distance between two 3D points
+ *
+ * @param a
+ * @param b
+ * @return
+ */
+ double distance3D(robot_msgs::Point a, robot_msgs::Point b)
+ {
+ return sqrt((a.x - b.x) * (a.x - b.x) + (a.y - b.y) * (a.y - b.y) + (a.z - b.z) * (a.z - b.z));
+ }
+
+ /**
+ * \brief Computes size and center of ROI in real-world
+ *
+ * Given a disparity images and a ROI in the image this function computes the approximate real-world size
+ * and center of the ROI.
+ *
+ * This function is just an approximation, it uses the mean value of the disparity in the ROI and assumes
+ * the ROI is flat region perpendicular on the camera z axis. It could be improved by finding a dominant plane
+ * in the and using only those disparity values.
+ *
+ * @param R
+ * @param meanDisparity
+ * @param dx
+ * @param dy
+ * @param center
+ */
+ void getROIDimensions(const CvRect& r, double & dx, double & dy, robot_msgs::Point & center)
+ {
+ // initialize stereo camera model
+ double Fx = rcinfo.P[0];
+ double Fy = rcinfo.P[5];
+ double Clx = rcinfo.P[2];
+ double Crx = Clx;
+ double Cy = rcinfo.P[6];
+ double Tx = -rcinfo.P[3] / Fx;
+ CvStereoCamModel cam_model(Fx, Fy, Tx, Clx, Crx, Cy, 4.0 / (double)dispinfo.dpp);
+
+ double mean = 0;
+ disparitySTD(disp, r, mean);
+
+ robot_msgs::Point p1 = disparityTo3D(cam_model, r.x, r.y, mean);
+ robot_msgs::Point p2 = disparityTo3D(cam_model, r.x + r.width, r.y, mean);
+ robot_msgs::Point p3 = disparityTo3D(cam_model, r.x, r.y + r.height, mean);
+ center = disparityTo3D(cam_model, r.x + r.width / 2, r.y + r.height / 2, mean);
+ dx = distance3D(p1, p2);
+ dy = distance3D(p1, p3);
+ }
+
+
+ /**
+ * \brief Publishes a visualization marker for a point.
+ * @param p
+ */
+ void showHandleMarker(robot_msgs::PointStamped p)
+ {
+ robot_msgs::VisualizationMarker marker;
+ marker.header.frame_id = p.header.frame_id;
+ marker.header.stamp = ros::Time((uint64_t)(0ULL));
+ marker.id = 0;
+ marker.type = robot_msgs::VisualizationMarker::SPHERE;
+ marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.x = p.point.x;
+ marker.y = p.point.y;
+ marker.z = p.point.z;
+ marker.yaw = 0.0;
+ marker.pitch = 0.0;
+ marker.roll = 0.0;
+ marker.xScale = 0.1;
+ marker.yScale = 0.1;
+ marker.zScale = 0.1;
+ marker.alpha = 255;
+ marker.r = 0;
+ marker.g = 255;
+ marker.b = 0;
+ publish("visualizationMarker", marker);
+ }
+
+
+
+// void showPlaneMarker(CvScalar plane, robot_msgs::PointCloud pc)
+// {
+//
+// double min_d = 10000;
+// int min_i = -1;
+// for (size_t i=0;i<pc.pts.size();++i) {
+// float dist = fabs(plane.val[0]*pc.pts[i].x+plane.val[1]*pc.pts[i].y+plane.val[2]*pc.pts[i].z+plane.val[3]);
+// if (dist<min_d) {
+// min_d = dist;
+// min_i = i;
+// }
+// }
+//
+//
+// robot_msgs::VisualizationMarker marker;
+// marker.header.frame_id = pc.header.frame_id;
+// marker.header.stamp = pc.header.stamp;
+// marker.id = 1211;
+// marker.type = robot_msgs::VisualizationMarker::SPHERE;
+// marker.action = robot_msgs::VisualizationMarker::ADD;
+// marker.x = pc.pts[min_i].x;
+// marker.y = pc.pts[min_i].y;
+// marker.z = pc.pts[min_i].z;
+// marker.yaw = 0.0;
+// marker.pitch = 0.0;
+// marker.roll = 0.0;
+// marker.xScale = 0.1;
+// marker.yScale = 0.1;
+// marker.zScale = 0.1;
+// marker.alpha = 255;
+// marker.r = 255;
+// marker.g = 0;
+// marker.b = 0;
+// publish("visualizationMarker", marker);
+//
+// printf("Show marker at: (%f,%f,%f)", marker.x, marker.y, marker.z);
+// }
+
+ /**
+ * \brief Determine if it's possible for handle to be in a specific ROI
+ *
+ * It looks at things like, height, approximate size of ROI, how flat it is.
+ *
+ * @param r
+ * @return
+ */
+ bool handlePossibleHere(const CvRect &r)
+ {
+ const float nz_fraction = 0.1;
+
+ cvSetImageROI(disp, r);
+ cvSetImageCOI(disp, 1);
+ int cnt = cvCountNonZero(disp);
+ cvResetImageROI(disp);
+ cvSetImageCOI(disp, 0);
+
+ if(cnt < nz_fraction * r.width * r.height){
+ return false;
+ }
+
+ // compute least-squares handle plane
+ robot_msgs::PointCloud pc = filterPointCloud(r);
+ CvScalar plane = estimatePlaneLS(pc);
+
+ cnt = 0;
+ double sum = 0;
+ double max_dist = 0;
+ for(size_t i = 0;i < pc.pts.size();++i){
+ robot_msgs::Point32 p = pc.pts[i];
+ double dist = fabs(plane.val[0] * p.x + plane.val[1] * p.y + plane.val[2] * p.z + plane.val[3]);
+ max_dist = max(max_dist, dist);
+ sum += dist;
+ cnt++;
+ }
+ sum /= cnt;
+ if(max_dist > 0.1 || sum < 0.005){
+ return false;
+ }
+
+ double dx, dy;
+ robot_msgs::Point p;
+ getROIDimensions(r, dx, dy, p);
+ if(dx > 0.25 || dy > 0.15){
+ ROS_INFO("Too big, discarding");
+ return false;
+ }
+
+ robot_msgs::PointStamped pin, pout;
+ pin.header.frame_id = cloud.header.frame_id;
+ pin.header.stamp = cloud.header.stamp;
+ pin.point.x = p.z;
+ pin.point.y = -p.x;
+ pin.point.z = -p.y;
+ try {
+ tf_->transformPoint("base_link", pin, pout);
+ }
+ catch(tf::LookupException & ex){
+ ROS_ERROR("Lookup exception: %s\n", ex.what());
+ }
+ catch(tf::ExtrapolationException & ex){
+ ROS_DEBUG("Extrapolation exception: %s\n", ex.what());
+ }
+ catch(tf::ConnectivityException & ex){
+ ROS_ERROR("Connectivity exception: %s\n", ex.what());
+ }
+
+ if(pout.point.z > max_height || pout.point.z < min_height){
+ return false;
+ }
+
+ printf("Handle at: (%d,%d,%d,%d)\n", r.x,r.y,r.width, r.height);
+
+
+ return true;
+ }
+
+ /**
+ * \brief Start handle detection
+ */
+ void findHandleCascade(vector<CvRect> & handle_rect)
+ {
+ IplImage *gray = cvCreateImage(cvSize(left->width, left->height), 8, 1);
+ cvCvtColor(left, gray, CV_BGR2GRAY);
+ cvEqualizeHist(gray, gray);
+ cvClearMemStorage(storage);
+ if(cascade){
+ CvSeq *handles = cvHaarDetectObjects(gray, cascade, storage, 1.1, 2, 0, //|CV_HAAR_FIND_BIGGEST_OBJECT
+ //|CV_HAAR_DO_ROUGH_SEARCH
+ //|CV_HAAR_DO_CANNY_PRUNING
+ //|CV_HAAR_SCALE_IMAGE
+ cvSize(10, 10));
+ for(int i = 0;i < (handles ? handles->total : 0);i++){
+ CvRect *r = (CvRect*)cvGetSeqElem(handles, i);
+
+ if(handlePossibleHere(*r)){
+ handle_rect.push_back(*r);
+// if(display){
+// cvRectangle(left, cvPoint(r->x, r->y), cvPoint(r->x + r->width, r->y + r->height), CV_RGB(0, 255, 0));
+// }
+ }
+ else{
+ // cvRectangle(left, cvPoint(r->x, r->y), cvPoint(r->x + r->width, r->y + r->height), CV_RGB(255, 0, 0));
+ }
+ }
+
+ }
+ else {
+ ROS_ERROR("Cannot look for handle, no detector loaded");
+ }
+
+ cvReleaseImage(&gray);
+ }
+
+ /**
+ * \brief Finds edges in an image
+ * @param img
+ */
+ void findEdges(IplImage *img)
+ {
+ IplImage *gray = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1);
+ cvCvtColor(img, gray, CV_RGB2GRAY);
+ cvCanny(gray, gray, 20, 40);
+ CvMemStorage *storage = cvCreateMemStorage(0);
+ CvSeq *lines = 0;
+ lines = cvHoughLines2(gray, storage, CV_HOUGH_PROBABILISTIC, 1, CV_PI / 360, 100, 200, 100);
+ for(int i = 0;i < lines->total;i++){
+ CvPoint *line = (CvPoint*)cvGetSeqElem(lines, i);
+ CvPoint p1 = line[0];
+ CvPoint p2 = line[1];
+ if(abs(p1.x - p2.x) > 0){
+ float min_angle = 80;
+ float slope = float(abs(p1.y - p2.y)) / abs(p1.x - p2.x);
+ float min_slope = tan(CV_PI / 2 - min_angle * CV_PI / 180);
+ if(slope < min_slope)
+ continue;
+
+ printf("slope: %f, min_slope: %f\n", slope, min_slope);
+ }
+ cvLine(left, p1, p2, CV_RGB(255, 0, 0), 2, CV_AA, 0);
+ }
+
+ cvReleaseImage(&gray);
+ }
+
+ /**
+ * \brief Checks if a point should belong to a cluster
+ *
+ * @param center
+ * @param p
+ * @return
+ */
+ bool belongsToCluster(pair<float,float> center, pair<float,float> p)
+ {
+ return fabs(center.first-p.first)<3 && fabs(center.second-p.second)<3;
+ }
+
+
+ /**
+ * Helper function.
+ *
+ * @param r
+ * @return
+ */
+ pair<float,float> rectCenter(const CvRect& r)
+ {
+ return make_pair(r.x+(float)r.width/2,r.y+(float)r.height/2);
+ }
+
+ /**
+ * \brief Decide the handle position from several detections across multiple frames
+ *
+ * This method does some simple clustering of all the bounding boxes and picks the cluster with
+ * the most elements.
+ *
+ * @param handle_rect The handle bounding boxes
+ * @param handle Point indicating the real-world handle position
+ * @return
+ */
+ bool decideHandlePosition(vector<CvRect>& handle_rect, robot_msgs::PointStamped & handle)
+ {
+ if (handle_rect.size()==0) {
+ return false;
+ }
+
+ vector<int> cluster_size;
+ vector<pair<float,float> > centers;
+ vector<pair<float,float> > sizes;
+
+ for (size_t i=0;i<handle_rect.size();++i) {
+ CvRect r = handle_rect[i];
+ pair<float,float> crt = rectCenter(r);
+ bool found_cluster = false;
+ for (size_t j=0;j<centers.size();++j) {
+ if (belongsToCluster(centers[j],crt)) {
+ int n = cluster_size[j];
+ centers[j].first = (centers[j].first*n+crt.first)/(n+1);
+ centers[j].second = (centers[j].second*n+crt.second)/(n+1);
+ sizes[j].first = (sizes[j].first*n+r.width)/(n+1);
+ sizes[j].second = (sizes[j].second*n+r.height)/(n+1);
+ cluster_size[j]++;
+ found_cluster = true;
+ break;
+ }
+ }
+ if (!found_cluster) {
+ centers.push_back(crt);
+ sizes.push_back(make_pair(r.width,r.height));
+ cluster_size.push_back(1);
+ }
+ }
+
+ int max_ind = 0;
+ int max = cluster_size[0];
+
+ for (size_t i=0;i<cluster_size.size();++i) {
+ if (cluster_size[i]>max) {
+ max = cluster_size[i];
+ max_ind = i;
+ }
+ }
+
+ CvRect bbox;
+ bbox.x = (int) centers[max_ind].first-(int)(sizes[max_ind].first/2);
+ bbox.y = (int) centers[max_ind].second-(int)(sizes[max_ind].second/2);
+ bbox.width = (int) sizes[max_ind].first;
+ bbox.height = (int) sizes[max_ind].second;
+
+ double dx, dy;
+ robot_msgs::Point p;
+ getROIDimensions(bbox, dx, dy, p);
+
+ handle.header.frame_id = cloud.header.frame_id;
+ handle.header.stamp = cloud.header.stamp;
+ handle.point.x = p.z;
+ handle.point.y = -p.x;
+ handle.point.z = -p.y;
+
+
+ printf("Clustered Handle at: (%d,%d,%d,%d)\n", bbox.x,bbox.y,bbox.width, bbox.height);
+
+
+ if(display){
+ cvRectangle(left, cvPoint(bbox.x, bbox.y), cvPoint(bbox.x + bbox.width, bbox.y + bbox.height), CV_RGB(0, 255, 0));
+ cvShowImage("left", left);
+ }
+// showHandleMarker(handle);
+
+ return true;
+ }
+
+
+ /**
+ * \brief Runs the handle detector
+ *
+ * @param handle Position of detected handle
+ * @return True if handle was found, false otherwise.
+ */
+ bool runHandleDetector(robot_msgs::PointStamped & handle)
+ {
+ vector<CvRect> handle_rect;
+
+ // acquire cv_mutex lock
+ boost::unique_lock<boost::mutex> images_lock(cv_mutex);
+
+ for (int i=0;i<frames_no;++i) {
+
+ printf("Waiting for images\n");
+ // block until images are available to process
+ images_ready.wait(images_lock);
+
+ printf("Woke up, processing images\n");
+
+ if(display){
+ // show original disparity
+ cvShowImage("disparity_original", disp);
+ }
+ // eliminate from disparity locations that cannot contain a handle
+ applyPositionPrior();
+ // run cascade classifier
+ findHandleCascade(handle_rect);
+ if(display){
+ // show filtered disparity
+ cvShowImage("disparity", disp);
+ // show left image
+ cvShowImage("left", left);
+ }
+ }
+
+ bool found = decideHandlePosition(handle_rect, handle);
+ return found;
+ }
+
+ /**
+ * \brief Service call to detect doors
+ */
+ bool detectHandleSrv(door_handle_detector::DoorsDetector::Request & req, door_handle_detector::DoorsDetector::Response & resp)
+ {
+
+ robot_msgs::PointStamped handle;
+ subscribeStereoData();
+ bool found = runHandleDetector(handle);
+ unsubscribeStereoData();
+
+ if(!found){
+ return false;
+ }
+ robot_msgs::PointStamped handle_transformed;
+ // transform the point in the expected frame
+ try {
+ tf_->transformPoint(req.door.header.frame_id, handle, handle_transformed);
+ }
+ catch(tf::LookupException & ex){
+ ROS_ERROR("Lookup exception: %s\n", ex.what());
+ }
+ catch(tf::ExtrapolationException & ex){
+ ROS_DEBUG("Extrapolation exception: %s\n", ex.what());
+ }
+ catch(tf::ConnectivityException & ex){
+ ROS_ERROR("Connectivity exception: %s\n", ex.what());
+ }
+ if(found){
+ resp.doors.resize(1);
+ resp.doors[0] = req.door;
+ resp.doors[0].handle.x = handle.point.x;
+ resp.doors[0].handle.y = handle.point.y;
+ resp.doors[0].handle.z = handle.point.z;
+ resp.doors[0].weight = 1;
+ }else{
+ resp.doors[0].weight = -1;
+ }
+ return true;
+ }
+
+
+ /**
+ * \brief Filters a cloud point, retains only points coming from a specific region in the disparity image
+ *
+ * @param rect Region in disparity image
+ * @return Filtered point cloud
+ */
+ robot_msgs::PointCloud filterPointCloud(const CvRect & rect)
+ {
+ robot_msgs::PointCloud result;
+ result.header.frame_id = cloud.header.frame_id;
+ result.header.stamp = cloud.header.stamp;
+ int xchan = -1;
+ int ychan = -1;
+ for(size_t i = 0;i < cloud.chan.size();++i){
+ if(cloud.chan[i].name == "x"){
+ xchan = i;
+ }
+ if(cloud.chan[i].name == "y"){
+ ychan = i;
+ }
+ }
+
+ if(xchan != -1 && ychan != -1){
+ for(size_t i = 0;i < cloud.pts.size();++i){
+ int x = (int)(cloud.chan[xchan].vals[i]);
+ int y = (int)(cloud.chan[ychan].vals[i]);
+ if(x >= rect.x && x < rect.x + rect.width && y >= rect.y && y < rect.y + rect.height){
+ result.pts.push_back(cloud.pts[i]);
+ }
+ }
+
+ }
+
+ return result;
+ }
+
+ /**
+ * \brief Computes a least-squares estimate of a plane.
+ *
+ * @param points The point cloud
+ * @return Plane in Hessian normal form
+ */
+ CvScalar estimatePlaneLS(robot_msgs::PointCloud points)
+ {
+ int cnt = points.pts.size();
+ CvMat *A = cvCreateMat(cnt, 3, CV_32FC1);
+ for(int i = 0;i < cnt;++i){
+ robot_msgs::Point32 p = points.pts[i];
+ cvmSet(A, i, 0, p.x);
+ cvmSet(A, i, 1, p.y);
+ cvmSet(A, i, 2, p.z);
+ }
+ vector<float> ones(cnt, 1);
+ CvMat B;
+ cvInitMatHeader(&B, cnt, 1, CV_32FC1, &ones[0]);
+ CvMat *X = cvCreateMat(3, 1, CV_32FC1);
+ int ok = cvSolve(A, &B, X, CV_SVD);
+ CvScalar plane;
+ if(ok){
+ float *xp = X->data.fl;
+ float d = sqrt(xp[0] * xp[0] + xp[1] * xp[1] + xp[2] * xp[2]);
+ plane.val[0] = xp[0] / d;
+ plane.val[1] = xp[1] / d;
+ plane.val[2] = xp[2] / d;
+ plane.val[3] = -1 / d;
+ }else{
+ plane.val[0] = plane.val[1] = plane.val[2] = plane.val[3] = -1;
+ }
+ cvReleaseMat(&A);
+ return plane;
+ }
+
+ /**
+ * \brief Filters cloud point, retains only regions that could contain a handle
+ */
+ void applyPositionPrior()
+ {
+ robot_msgs::PointCloud base_cloud;
+ tf_->setExtrapolationLimit(ros::Duration(2.0));
+ try {
+ tf_->transformPointCloud("base_link", cloud, base_cloud);
+ }
+ catch(tf::ExtrapolationException & ex){
+ tf_->clear();
+ ROS_WARN("TF exception: %s", ex.what());
+ }
+ catch(tf::LookupException & ex){
+ ROS_ERROR("Lookup exception: %s\n", ex.what());
+ }
+ catch(tf::ConnectivityException & ex){
+ ROS_ERROR("Connectivity exception: %s\n", ex.what());
+ }
+ int xchan = -1;
+ int ychan = -1;
+ for(size_t i = 0;i < base_cloud.chan.size();++i){
+ if(base_cloud.chan[i].name == "x"){
+ xchan = i;
+ }
+ if(base_cloud.chan[i].name == "y"){
+ ychan = i;
+ }
+ }
+
+ if(xchan != -1 && ychan != -1){
+ unsigned char *pd = (unsigned char*)(disp->imageData);
+ int ws = disp->widthStep;
+ for(size_t i = 0;i < base_cloud.get_pts_size();++i){
+ robot_msgs::Point32 crt_point = base_cloud.pts[i];
+ int x = (int)(base_cloud.chan[xchan].vals[i]);
+ int y = (int)(base_cloud.chan[ychan].vals[i]);
+
+ // pointer to the current pixel
+ unsigned char* crt_pd = pd+y*ws+x;
+ if (crt_point.z>max_height || crt_point.z<min_height) {
+ *crt_pd = 0;
+ }
+ }
+ }
+ else {
+ ROS_WARN("I can't find image coordinates in the point cloud, no filtering done.");
+ }
+ }
+
+
+ /**
+ * Callback from topic synchronizer, timeout
+ * @param t
+ */
+ void image_cb_timeout(ros::Time t)
+ {
+ if(limage.header.stamp != t) {
+ printf("Timed out waiting for left image\n");
+ }
+
+ if(dimage.header.stamp != t) {
+ printf("Timed out waiting for disparity image\n");
+ }
+
+ if(stinfo.header.stamp != t) {
+ printf("Timed out waiting for stereo info\n");
+ }
+
+ if(cloud_fetch.header.stamp != t) {
+ printf("Timed out waiting for point cloud\n");
+ }
+ }
+
+
+ /**
+ * Callback from topic synchronizer, images ready to be consumed
+ * @param t
+ */
+ void image_cb_all(ros::Time t)
+ {
+ // obtain lock on vision data
+ boost::lock_guard<boost::mutex> lock(cv_mutex);
+
+ if(lbridge.fromImage(limage, "bgr")){
+ if(left != NULL)
+ cvReleaseImage(&left);
+
+ left = cvCloneImage(lbridge.toIpl());
+ }
+ if(rbridge.fromImage(rimage, "bgr")){
+ if(right != NULL)
+ cvReleaseImage(&right);
+
+ right = cvCloneImage(rbridge.toIpl());
+ }
+ if(dbridge.fromImage(dimage)){
+ if(disp != NULL)
+ cvReleaseImage(&disp);
+
+ disp = cvCreateImage(cvGetSize(dbridge.toIpl()), IPL_DEPTH_8U, 1);
+ cvCvtScale(dbridge.toIpl(), disp, 4.0 / dispinfo.dpp);
+ }
+
+ cloud = cloud_fetch;
+
+ images_ready.notify_all();
+ }
+
+
+
+public:
+ /**
+ * Needed for OpenCV event loop, to show images
+ * @return
+ */
+ bool spin()
+ {
+ while (ok())
+ {
+ cv_mutex.lock();
+ int key = cvWaitKey(3)&0x00FF;
+ if(key == 27) //ESC
+ break;
+
+ cv_mutex.unlock();
+ usleep(10000);
+ }
+
+ return true;
+ }
+};
+
+int main(int argc, char **argv)
+{
+ for(int i = 0; i<argc; ++i)
+ cout << "(" << i << "): " << argv[i] << endl;
+
+ ros::init(argc, argv);
+ HandleDetector view;
+ view.spin();
+
+ return 0;
+}
+
Deleted: pkg/trunk/vision/door_handle_detect/CMakeLists.txt
===================================================================
--- pkg/trunk/vision/door_handle_detect/CMakeLists.txt 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/vision/door_handle_detect/CMakeLists.txt 2009-04-02 18:44:12 UTC (rev 13319)
@@ -1,10 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-rospack(door_handle_detect)
-
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-
-rospack_add_executable(door_handle_detect src/door_handle_detect.cpp)
-
-rospack_add_executable(test_service src/test.cpp)
Deleted: pkg/trunk/vision/door_handle_detect/Makefile
===================================================================
--- pkg/trunk/vision/door_handle_detect/Makefile 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/vision/door_handle_detect/Makefile 2009-04-02 18:44:12 UTC (rev 13319)
@@ -1 +0,0 @@
-include $(shell rospack find mk)/cmake.mk
Deleted: pkg/trunk/vision/door_handle_detect/data/annotate.py
===================================================================
--- pkg/trunk/vision/door_handle_detect/data/annotate.py 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/vision/door_handle_detect/data/annotate.py 2009-04-02 18:44:12 UTC (rev 13319)
@@ -1,100 +0,0 @@
-from opencv.highgui import *
-from opencv.cv import *
-import numpy
-import scipy
-import sys
-import os
-from string import split
-
-image = None
-image_clone = None
-in_draw = False
-
-bb_list = []
-
-def show_bb(image, bbs):
- pass
-
-
-def on_mouse(event, x, y, flags, p ):
- global start, image, image_clone, in_draw
-
- if not image:
- return
-
- cvCopy(image_clone,image)
-
- if event == CV_EVENT_LBUTTONDOWN:
- start = (x,y)
- in_draw = True
- if event == CV_EVENT_MOUSEMOVE:
- if in_draw:
- start_x = min(start[0],x)
- start_y = min(start[1],y)
- end_x = max(start[0],x)
- end_y = max(start[1],y)
- cvRectangle(image, cvPoint(start_x,start_y), cvPoint(end_x,end_y),CV_RGB(255,0,0))
- elif event == CV_EVENT_LBUTTONUP:
- if in_draw:
- in_draw = False
- start_x = min(start[0],x)
- start_y = min(start[1],y)
- end_x = max(start[0],x)
- end_y = max(start[1],y)
- cvRectangle(image_clone, cvPoint(start_x,start_y), cvPoint(end_x,end_y),CV_RGB(255,0,0))
- cvRectangle(image, cvPoint(start_x,start_y), cvPoint(end_x,end_y),CV_RGB(255,0,0))
- bb_list.append((start_x,start_y,end_x,end_y))
-
-
- cvShowImage("image",image)
-
-
-def read_bb(bb_name):
- global bb_dict
- bb_file = open(bb_name,"r")
- for line in bb_file:
- items = split(line)
- bb_dict[items[0]] = map(int,items[1:])
- bb_file.close()
- return bb_dict
-
-def annotate(image_name, bb_name):
- global image, image_clone, bb_list
- #bb_dict = read_bb(bb_name)
- image = cvLoadImage(image_name)
- image_clone = cvCloneImage(image)
-
-
- cvNamedWindow("image",1)
- cvShowImage("image",image)
- cvSetMouseCallback( "image", on_mouse, None );
-
- while True:
- c = '%c' % (cvWaitKey(0) & 255)
-
- if( c == '\x1b' or c=='q'):
- print "Exiting, not saving to file"
- break;
-
- if c=='s':
- print "Exiting, saving to file: %s"%bb_name
- file = open(bb_name,"a")
- print >>file, image_name,
- for bb in bb_list:
- for x in bb:
- print >>file, x,
- print >>file
- file.close()
- break;
-
-
-
-if __name__=="__main__":
- if len(sys.argv)<3:
- print "Usage: annotate.py bb_file image"
- sys.exit(1)
-
- annotate(sys.argv[2], sys.argv[1])
-
-
-
Deleted: pkg/trunk/vision/door_handle_detect/data/convert.py
===================================================================
--- pkg/trunk/vision/door_handle_detect/data/convert.py 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/vision/door_handle_detect/data/convert.py 2009-04-02 18:44:12 UTC (rev 13319)
@@ -1,57 +0,0 @@
-from opencv import *
-import numpy
-import scipy
-import sys
-import os
-from string import split, strip
-import itertools
-from array import array
-from scipy.io.numpyio import fwrite, fread
-
-
-
-
-def group(lst, n):
- """group([0,3,4,10,2,3], 2) => iterator
-
- Group an iterable into an n-tuples iterable. Incomplete tuples
- are discarded e.g.
-
- >>> list(group(range(10), 3))
- [(0, 1, 2), (3, 4, 5), (6, 7, 8)]
- """
- return itertools.izip(*[itertools.islice(lst, i, None, n) for i in range(n)])
-
-
-def read_bb(bb_name):
- bb_dict = {}
- bb_file = open(bb_name,"r")
- for line in bb_file:
- items = split(line)
- bb_dict[items[0]] = map(int,items[1:])
- bb_file.close()
- return bb_dict
-
-
-def convert(bb_name, output_file):
- bb_dict = read_bb(bb_name)
- bb_cv_dict = {}
- file = open(output_file,"w")
- for key, bb_list in bb_dict.items():
- count = 0
- for i in range(0,len(bb_list),4):
- bb_list[i+2] -= bb_list[i]
- bb_list[i+3] -= bb_list[i+1]
- count +=1
- print >>file, key, count,
- for bb in bb_list:
- print >>file, bb,
- print >>file
-
-if __name__=="__main__":
- if len(sys.argv)<2:
- print "Usage: %s input_file output_file"%sys.argv[0]
- sys.exit(1)
-
- convert(sys.argv[1], sys.argv[2])
-
\ No newline at end of file
Deleted: pkg/trunk/vision/door_handle_detect/data/handles_data.xml
===================================================================
--- pkg/trunk/vision/door_handle_detect/data/handles_data.xml 2009-04-02 18:43:22 UTC (rev 13318)
+++ pkg/trunk/vision/door_handle_detect/data/handles_data.xml 2009-04-02 18:44:12 UTC (rev 13319)
@@ -1,2383 +0,0 @@
-<?xml version="1.0"?>
-<opencv_storage>
-<handles_data type_id="opencv-haar-classifier">
- <size>
- 80 40</size>
- <stages>
- <_>
- <!-- stage 0 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 14 32 28 8 -1.</_>
- <_>
- 14 36 28 4 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>7.9556362470611930e-04</threshold>
- <left_val>-0.7668160796165466</left_val>
- <right_val>0.8680202960968018</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 34 34 39 6 -1.</_>
- <_>
- 34 37 39 3 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>3.8265390321612358e-04</threshold>
- <left_val>-0.7227920889854431</left_val>
- <right_val>0.6177240014076233</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 21 6 40 6 -1.</_>
- <_>
- 21 9 40 3 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-1.9062459468841553e-03</threshold>
- <left_val>0.7472105026245117</left_val>
- <right_val>-0.6904346942901611</right_val></_></_></trees>
- <stage_threshold>-0.8395267724990845</stage_threshold>
- <parent>-1</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 1 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 30 32 28 8 -1.</_>
- <_>
- 30 36 28 4 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>3.8088040892034769e-03</threshold>
- <left_val>-0.7130435109138489</left_val>
- <right_val>0.8631579279899597</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 26 22 36 15 -1.</_>
- <_>
- 26 27 36 5 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0227580908685923</threshold>
- <left_val>0.9769784212112427</left_val>
- <right_val>-0.3723630011081696</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 7 34 38 6 -1.</_>
- <_>
- 7 37 38 3 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>7.4299727566540241e-04</threshold>
- <left_val>-0.6546555161476135</left_val>
- <right_val>0.6376091241836548</right_val></_></_></trees>
- <stage_threshold>-0.4477972984313965</stage_threshold>
- <parent>0</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 2 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 31 0 4 22 -1.</_>
- <_>
- 31 11 4 11 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-5.7610089424997568e-04</threshold>
- <left_val>0.5815898776054382</left_val>
- <right_val>-0.7679557800292969</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 21 22 40 18 -1.</_>
- <_>
- 21 28 40 6 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0375104509294033</threshold>
- <left_val>0.7651547789573669</left_val>
- <right_val>-0.5128406286239624</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 15 0 3 14 -1.</_>
- <_>
- 15 7 3 7 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-5.0383659981889650e-05</threshold>
- <left_val>0.5075067281723022</left_val>
- <right_val>-0.7586528062820435</right_val></_></_></trees>
- <stage_threshold>-0.7732896804809570</stage_threshold>
- <parent>1</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 3 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 25 25 22 15 -1.</_>
- <_>
- 25 30 22 5 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0223254896700382</threshold>
- <left_val>0.7307692170143127</left_val>
- <right_val>-0.4318181872367859</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 35 0 39 22 -1.</_>
- <_>
- 35 11 39 11 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0347877293825150</threshold>
- <left_val>0.6509677767753601</left_val>
- <right_val>-0.5333423018455505</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 0 38 18 2 -1.</_>
- <_>
- 0 39 18 1 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-1.8058849673252553e-04</threshold>
- <left_val>-0.8768190741539001</left_val>
- <right_val>0.3655551075935364</right_val></_></_>
- <_>
- <!-- tree 3 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 4 37 15 3 -1.</_>
- <_>
- 4 38 15 1 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-2.4448329349979758e-04</threshold>
- <left_val>-0.9017577171325684</left_val>
- <right_val>0.3027119040489197</right_val></_></_>
- <_>
- <!-- tree 4 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 31 19 40 14 -1.</_>
- <_>
- 31 26 40 7 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0437914505600929</threshold>
- <left_val>0.7599353790283203</left_val>
- <right_val>-0.4327661991119385</right_val></_></_>
- <_>
- <!-- tree 5 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 47 6 30 26 -1.</_>
- <_>
- 47 6 15 13 2.</_>
- <_>
- 62 19 15 13 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0207422003149986</threshold>
- <left_val>0.7396255731582642</left_val>
- <right_val>-0.3553375005722046</right_val></_></_>
- <_>
- <!-- tree 6 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 47 32 6 7 -1.</_>
- <_>
- 49 32 2 7 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>2.9371608980000019e-04</threshold>
- <left_val>0.3532634973526001</left_val>
- <right_val>-0.8004472255706787</right_val></_></_></trees>
- <stage_threshold>-0.8412402272224426</stage_threshold>
- <parent>2</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 4 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 33 23 17 15 -1.</_>
- <_>
- 33 28 17 5 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0248114392161369</threshold>
- <left_val>0.7226278185844421</left_val>
- <right_val>-0.3498232960700989</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 68 6 12 32 -1.</_>
- <_>
- 72 6 4 32 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-3.6221379414200783e-03</threshold>
- <left_val>0.6445968747138977</left_val>
- <right_val>-0.3200798928737640</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 18 28 37 6 -1.</_>
- <_>
- 18 31 37 3 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0131213497370481</threshold>
- <left_val>0.8235750198364258</left_val>
- <right_val>-0.2439347058534622</right_val></_></_>
- <_>
- <!-- tree 3 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 37 11 10 18 -1.</_>
- <_>
- 37 20 10 9 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0199232902377844</threshold>
- <left_val>0.8326957225799561</left_val>
- <right_val>-0.2833735048770905</right_val></_></_>
- <_>
- <!-- tree 4 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 45 17 30 10 -1.</_>
- <_>
- 45 17 15 5 2.</_>
- <_>
- 60 22 15 5 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-5.1957601681351662e-03</threshold>
- <left_val>0.6790230870246887</left_val>
- <right_val>-0.2986282110214233</right_val></_></_></trees>
- <stage_threshold>-0.5311627984046936</stage_threshold>
- <parent>3</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 5 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 0 2 2 12 -1.</_>
- <_>
- 0 8 2 6 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>2.1357160585466772e-04</threshold>
- <left_val>0.2515336871147156</left_val>
- <right_val>-0.8723403811454773</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 76 14 4 14 -1.</_>
- <_>
- 78 14 2 14 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>6.9165299646556377e-04</threshold>
- <left_val>-0.4245294928550720</left_val>
- <right_val>0.5808904170989990</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 25 25 1 6 -1.</_>
- <_>
- 25 27 1 2 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-2.6425538817420602e-04</threshold>
- <left_val>0.7798237204551697</left_val>
- <right_val>-0.2664712965488434</right_val></_></_>
- <_>
- <!-- tree 3 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 17 0 10 18 -1.</_>
- <_>
- 17 9 10 9 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-2.1467849146574736e-03</threshold>
- <left_val>0.3556644022464752</left_val>
- <right_val>-0.6652340292930603</right_val></_></_>
- <_>
- <!-- tree 4 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 7 18 14 10 -1.</_>
- <_>
- 7 18 7 5 2.</_>
- <_>
- 14 23 7 5 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>3.9194659329950809e-03</threshold>
- <left_val>-0.2328546047210693</left_val>
- <right_val>0.8990067243576050</right_val></_></_>
- <_>
- <!-- tree 5 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 18 17 1 8 -1.</_>
- <_>
- 18 21 1 4 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-2.5320390705019236e-04</threshold>
- <left_val>0.6481050848960876</left_val>
- <right_val>-0.4338380992412567</right_val></_></_>
- <_>
- <!-- tree 6 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 26 29 8 3 -1.</_>
- <_>
- 26 30 8 1 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-2.3106430307962000e-04</threshold>
- <left_val>0.6508073806762695</left_val>
- <right_val>-0.2905809879302979</right_val></_></_></trees>
- <stage_threshold>-0.2181423008441925</stage_threshold>
- <parent>4</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 6 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 0 18 6 10 -1.</_>
- <_>
- 3 18 3 10 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-1.1275060242041945e-03</threshold>
- <left_val>0.6595743894577026</left_val>
- <right_val>-0.3333333134651184</right_val></_></_>
- <_>
- <!-- tree 1 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 56 22 14 10 -1.</_>
- <_>
- 56 22 7 5 2.</_>
- <_>
- 63 27 7 5 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-3.9659561589360237e-03</threshold>
- <left_val>0.7412996888160706</left_val>
- <right_val>-0.2089336961507797</right_val></_></_>
- <_>
- <!-- tree 2 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 31 30 14 2 -1.</_>
- <_>
- 31 30 7 1 2.</_>
- <_>
- 38 31 7 1 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>4.8963102744892240e-04</threshold>
- <left_val>-0.2077756971120834</left_val>
- <right_val>0.8155772089958191</right_val></_></_>
- <_>
- <!-- tree 3 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 39 26 19 12 -1.</_>
- <_>
- 39 30 19 4 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0280914604663849</threshold>
- <left_val>0.7219129204750061</left_val>
- <right_val>-0.2462842017412186</right_val></_></_>
- <_>
- <!-- tree 4 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 12 12 24 22 -1.</_>
- <_>
- 12 12 12 11 2.</_>
- <_>
- 24 23 12 11 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-0.0247455295175314</threshold>
- <left_val>0.7494925260543823</left_val>
- <right_val>-0.2185737043619156</right_val></_></_>
- <_>
- <!-- tree 5 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 1 7 16 8 -1.</_>
- <_>
- 9 7 8 8 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-5.1483071729307994e-05</threshold>
- <left_val>0.4394671022891998</left_val>
- <right_val>-0.4419902861118317</right_val></_></_>
- <_>
- <!-- tree 6 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 48 24 24 6 -1.</_>
- <_>
- 48 24 12 3 2.</_>
- <_>
- 60 27 12 3 2.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>4.2422642000019550e-03</threshold>
- <left_val>-0.2691087126731873</left_val>
- <right_val>0.6843476891517639</right_val></_></_></trees>
- <stage_threshold>-0.9757661819458008</stage_threshold>
- <parent>5</parent>
- <next>-1</next></_>
- <_>
- <!-- stage 7 -->
- <trees>
- <_>
- <!-- tree 0 -->
- <_>
- <!-- root node -->
- <feature>
- <rects>
- <_>
- 1 16 18 16 -1.</_>
- <_>
- 7 16 6 16 3.</_></rects>
- <tilted>0</tilted></feature>
- <threshold>-8.6438432335853577e-03</threshold>
- <left_val>0.5675675868988037</left_val>
- <right_val>-0.3088234961032867</right_val></_></_>
- <_>
- <!-- tree 1 -->
- ...
[truncated message content] |