基于立体视觉的环境构建及机器人路径规划研究
详细信息    本馆镜像全文|  推荐本文 |  |   获取CNKI官网全文
摘要
移动机器人对外部环境的有效感知以及基于该感知信息的路径规划是实现其自主运动的前提和关键问题。双目立体视觉不但能够感知环境的影像信息,而且能够通过两幅视图的匹配关系构建场景三维数据,是获取场景三维空间信息的理想方式。六足机器人与其他类型的移动机器人相比,具有较强的地面适应能力和良好的运动稳定性。本文在六足机器人基础上研制双目立体视系统,使之具备三维信息感知能力,并且对六足机器人系统在复杂环境下的路径规划方法进行研究,具有重要的理论和实际应用价值。
     本文在对双目立体视觉构建原理进行深入分析的基础上,以六足机器人负载能力和应用特点为指标,设计小巧紧凑的双目立体视觉机构。完成以DSP为核心、以CAN总线为框架的分布式控制单元,实现了立体视觉与六足机器人系统的一体化设计,构成完善的具有三维信息感知能力的六足机器人系统。在此基础上对双目立体视觉系统使用的摄像机进行单目和双目的标定与校正,为后续的立体匹配研究提供理想的视图对和摄像机参数信息。
     立体视觉匹配研究中,采用全局最优匹配方法能够获取高精度视差图,本文针对全局最优立体匹配算法求解时间过长的问题进行深入研究,设计了两类立体匹配算法提高匹配速度。第一类匹配算法建立基于马尔科夫随机场最大后验概率模型的全局最优目标函数,采用最信度传播算法求取最优解。为进一步提高全局最优算法的求解速度,设计基于最优分割的信度传播改进算法。采用最优分割策略将视图分割为若干小的区域,将全局问题局部化,运用OpenMP多核加速技术对多个分割区域进行并行匹配,提高整体视图的匹配速度。通过最优分割与并行处理,算法的匹配时间减少到3秒以内,综合匹配精度达到91%;在第二类匹配算法中设计支撑点扩展快速匹配算法,采用形式更加简化的立体匹配目标函数进行匹配。算法首先搜索出具有明确匹配关系的点集并命名为支撑点,在整个视图空间的匹配中,以支撑点为核心向邻域扩展,在扩展区域的匹配过程中采用全局次优快速匹配算法。由于扩展空间以支撑点为邻域,因而利用支撑点的匹配结果为已知条件,有效缩减待待匹配区域的视差范围,进而提高匹配速度。算法匹配时间达到0.6秒以内,综合匹配精度达到78%,匹配速度有明显改善,能够达到实际应用的需求。
     以视差图为基础经过三维重投影恢复场景三维信息,采用基于隐式马尔科夫随机场模型识别方法对场景三维区域进行划分,将场景划分为通行区域与障碍区域,为机器人运动规划提供环境基础。
     针对局部信息路径规划问题,提出双层路径规划算法。双层路径规划算法由两个层次组成,分别是路径规划层和运动控制层。路径规划层中的快速搜索多边形构造方法能够在复杂环境下搜索出逃离障碍物的包围多边形,构建可视图,通过可视图优化获取最短路径;运动控制层采用“基于势场函数的机器人运动控制算法”,控制机器人实际运动,使机器人能够有效躲避障碍物并逐步趋向目标点。每个控制周期内,规划算法的两个步骤循环运行,控制机器人完成规划运动。
     为体现本文两类立体匹配算法的作用,设计了结合两类匹配算法优点的综合感知实验方法。综合感知方法对场景信息的获取通过两个步骤实现,首先采用快速支撑点扩展算法进行立体匹配,恢复场景三维信息,将场景分为通行区域和障碍区域。为保证通行区域内机器人运动的安全性,利用视差图与场景三维点的对应关系,采用高精度匹配算法对通行区域重新匹配以获取更精确的场景信息。
     在六足机器人路径规划实验研究中,设计六足机器人步行方法,该六足机器人步行方式与路径规划算法输出的结果相对应,进而验证路径规划算法的实际价值。实验中设计了平坦地面与粗糙地面两类实验环境,在两类环境中采用综合感知法、高精度感知法和快速感知法分别完成实验。实验结果表明,综合感知法能够获取更加理想的实验效果。六足机器人系统整体实验也充分验证了本文提出的三维构建算法、地面识别算法的实际效果和应用价值。
During the research of robot autonomy movement, the core subject is how to perceive the environment and decide their own motion planning. We design and realiz a binocular stereo vision mechanism system firstly. The mechanism of binocular stereo vision system has compact design, its electrical control system is designed based on distributed framework with CAN bus, in which DSP processor acts as the core. The motion controler uses servomotor as driver, which has high precision and flexibility. The binocular stereo vision mechanism system and the hexapod robot make up a perfect hexapod robot stereo vision platform. To acquire the intrinsic and external parameters of the cameras used in binocular system, we achieved monocular and binocular camera calibration respectively and provide ideal stereo image pairs and camera parameters for stereo matching study, the matching results lay the foundation for three-dimension scene construction.
     The disparity map is the basic for building three-dimensional information, and the matching algorithm is the hot point in researches on stereoscopic vision. Although local optimization stereo matching algorithm is easy to implement, it is usually has low quality which difficult to apply in real application. The global optimization algorithm, which building a high quality disparity map, is an emphases in the research of stereo matching. Currently available globally optimal algorithms can get high precision disparity map, but the matching time is relatively long and need several minutes usually.
     Two types of stereovision matching algorithm with high precision are designed in this paper. The first algorithm bases on MRF/MAP and use maximum accumulation rule of belief propagation algorithm to obtain disparity. In order to improve the matching speed, an global optimal division algorithm is designed. The algorithm uses optimal segmentation strategy to divide the whole image into a number of small areas, matching each independent split region using OpenMP acceleration tools to reduce overall disparity map matching time. Experimental results show that using optimal segmentation and parallel processing, the matching time of the improved belief propagation algorithm reduce to less than3seconds with overall accuracy of91%. Although global segmentation algorithm accelerate the matching time, it is hard to use in practical application still. To achieved real-time disparity matching, the support points expansion algorithm is designed to speed up the matching time. The algorithm redesigns simple objective function firstly. During the searching of optimal solution, design the support points expansion method. The matching points with a clear matching relationships, which named as support points are searched out. In subsequent step, expansion the neighborhood of the support points and matching the extended space. For the support point give the prior knowledge to the neighbor points, it reducing global solution space, thereby improving the matching speed. According to the results of the experiment, the matching time less than0.5seconds, the whole match accuracy up to78%, although its match quality is relatively lower than the global segmentation algorithms, the matching speed has improved greatly, which satisfied application requirements.
     After acquire disparity map, the three dimensional scene is recovered. The obstacle recognition method based on Hidden Markov Model is used to classify the scene, which supports environmental information for robot autonomy movement. In the research of robot autonomous motion, design a apposite way polygon construction algorithm and robot motion controller based on potential field function. Apposite way polygon construction algorithm can construct a surrounds polygons of the barrier in a complex environment, generate optimal paths pass through obstacles. Robot motion controller set attracting potential field function and repulsive potential field function as input vector, calculate speed and angle of the robot as output vector. The controller controls the robot movement, so that robots can effectively avoid obstacles and move towards target point; controller set the basic speed of the robot to solve local minimization problem caused by zero potential field. Experiments based on artificial map showed that compared with the artificial potential field-APF and wall-following–Bug, our method acquire better optimization path and real-time performance, with a wide range of practical applications.
     To reflect the value of the two matching algorithms in hexapod robot experiment, designed a comprehensive perception method. Comprehensive perception method composes with two steps. Using rapid stereo matching method to restore the entire scene3D points, with hidden Markov models to identify passable area. In order to ensure the safety of the robot in passable area, according the corresponding relationship between disparity map and3D points, using the high quality matching method to identify the passable area again to obtain more precise scene information. Experimental results show that compare with fast matching method or high quality matching method alone, comprehensive perception method is more effective in the total path length and total exercise time.
     To verify the value of our autonomous algorithm, rough terrain recognition algorithm and stereo matching algorithm, the final hexapod robot experiments are designed. Two types of ground is designed namely flat ground and rough ground. The experiments result show that the proposed algorithms have research value on the robot practical application.
引文
[1] David Marr, Tomaso Poggio, Ellen C Hildreth et al. A computational theory ofhuman stereo vision[C] Springer,1991:263-295.
    [2] Michael N Dille. Free LittleDog: Towards Completely Untethered Operation of theLittleDog Quadruped[C], DTIC Document,2007.
    [3] John R Rebula, Peter D Neuhaus, Brian V Bonnlander et al. A controller for thelittledog quadruped walking on rough terrain[C], Robotics and Automation,2007IEEE International Conference on,2007:1467-1473.
    [4] Alexander Shkolnik, Michael Levashov, Sara Itani et al..Motion planning forbounding on rough terrain with the little dog robot[C], Proc. of Int. Conf. onRobotics and Automation, Anchorage, Alaska. IEEE/RAS,2010.
    [5] K Walas,D Belter. Messor-Verstatile walking robot for search and rescuemissions[J]. Journal of Automation Mobile Robotics and Intelligent Systems.2011,5(2):28-34.
    [6] Adam Schmidt, Andrzej Kasiński. The visual SLAM system for a hexapod robot[C].Springer,2010:260-267.
    [7] M G rner,Th Wimb ck, G Hirzinger. The DLR Crawler: evaluation of gaits andcontrol of an actively compliant six-legged walking robot[J]. Industrial Robot: AnInternational Journal.2009,36(4):344-351.
    [8]韩晓建,丁相方.一种非完整轮式机器人的运动特性研究2013.
    [9]孙大伟.基于双目视觉的月球车导航方法研究[D]:哈尔滨工业大学,2010.
    [10] John Y Aloimonos.Perspective approximations[J].Image and Vision Computing.1990,8(3):179-192.
    [11] Emanuele Trucco. Geometric Invariance in Computer Vision[J].AI Communications.1995,8(3):193-194.
    [12] Oliver Faugeras. Three dimensional computer vision: A geometric viewpoint[M]:the MIT Press,1993.
    [13] Rajiv Gupta, Richard I Hartley. Linear pushbroom cameras[J]. Pattern Analysis andMachine Intelligence, IEEE Transactions on Image Processing.1997,19(9):963-975.
    [14] Long Quan,Takeo Kanade. Affine structure from line correspondences withuncalibrated affine cameras[J]. Pattern Analysis and Machine Intelligence, IEEETransactions on Image Processing.1997,19(8):834-845.
    [15] Long Quan. Uncalibrated1D projective camera and3D affine reconstruction oflines[C], Computer Vision and Pattern Recognition,1997. Proceedings,1997IEEEComputer Society Conference on,1997:60-65.
    [16] Richard I Hartley. Theory and practice of projective rectification[J].InternationalJournal of Computer Vision.1999,35(2):115-127.
    [17] Roger Tsai. A versatile camera calibration technique for high-accuracy3D machinevision metrology using off-the-shelf TV cameras and lenses[J]. Robotics andAutomation, IEEE Journal of.1987,3(4):323-344.
    [18] Zhengyou Zhang. Flexible camera calibration by viewing a plane from unknownorientations[C], Computer Vision,1999. The Proceedings of the Seventh IEEEInternational Conference,1999:666-673.
    [19] Xiao-Ming Deng, Fu-Chao Wu, Yi-Hong Wu. An easy calibration method forcentral catadioptric cameras[J]. Acta automatica sinica.2007,33(8):801-808.
    [20] Jianbo Su. Camera calibration based on receptive fields[J]. Pattern recognition.2007,40(10):2837-2845.
    [21] Jong-Eun Ha. Automatic detection of chessboard and its applications[J]. OpticalEngineering.2009,48(6):067205-067205-067208.
    [22] Jong-Eun Ha. Automatic detection of calibration markers on a chessboard[J]. OpticalEngineering.2007,46(10):107203-107203-107208.
    [23] Paulo J da Silva Tavares, M rio A Vaz. Accurate subpixel corner detection onplanar camera calibration targets[J]. Optical Engineering.2007,46(10):107205-107205-107208.
    [24]胡海峰,侯晓微.一种自动检测棋盘角点的新算法[J].计算机工程.2004,30(14):19-21.
    [25]王忠石,徐心和.棋盘格模板角点的自动识别与定位[J].中国图象图形学报.2007,12(4):618.
    [26] Zhongshi Wang, Wei Wu, Xinhe Xu et al. Recognition and location of the internalcorners of planar checkerboard calibration pattern image[J], Applied mathematicsand computation.2011,185(2):894-906.
    [27]熊会元,宗志坚,余志等.基于凸包的棋盘格角点自动识别与定位方法[J][J].中山大学学报:自然科学版.2009,48(1):1-5.
    [28]侯建辉,林意.自适应的Harris棋盘格角点检测算法[J].计算机工程与设计.2010,20):4741-4743.
    [29]孟晓桥,胡占义.一种新的基于圆环点的摄像机自标定方法[J].软件学报.2002,5:36-41
    [30] Daniel Scharstein, Richard Szeliski. A taxonomy and evaluation of dense two-framestereo correspondence algorithms[J]. International Journal of Computer Vision.2002,47(1-3):7-42.
    [31] Stefano Mattoccia, Federico Tombari, Luigi Di Stefano. Fast full-search equivalenttemplate matching by enhanced bounded correlation[J]. Image Processing, IEEETransactions.2008,17(4):528-538.
    [32] Luigi Di Stefano, Stefano Mattoccia, Federico Tombari. ZNCC-based templatematching using bounded partial correlation[J]. Pattern recognition letters.2005,26(14):2129-2134.
    [33] Federico Tombari, Luigi Di Stefano, Stefano Mattoccia et al..PerformanceEvaluation of Robust Matching Measures[C], VISAPP (1),2008:473-478.
    [34] Ramin Zabih, John Woodfill. Non-parametric local transforms for computing visualcorrespondence[C]. Springer,1994:151-158.
    [35] Dinkar N Bhat, Shree K Nayar. Ordinal measures for visual correspondence[C],Computer Vision and Pattern Recognition,1996. Proceedings CVPR'96,1996IEEEComputer Society Conference,1996:351-357.
    [36] Heiko Hirschmuller. Stereo vision in structured environments by consistentsemi-global matching[C], Computer Vision and Pattern Recognition,2006IEEEComputer Society Conference,2006:2386-2393.
    [37] Stan Birchfield, Carlo Tomasi. A pixel dissimilarity measure that is insensitive toimage sampling[J]. Pattern Analysis and Machine Intelligence, IEEE Transactions.1998,20(4):401-406.
    [38] Changming Sun. Moving average algorithms for diamond, hexagon, and generalpolygonal shaped window operations[J]. Pattern recognition letters.2006,27(6):556-566.
    [39] Olga Veksler. Fast variable window for stereo correspondence using integralimages[C],Computer Vision and Pattern Recognition,2003. Proceedings.2003IEEEComputer Society Conference,2003: I-556-I-561vol.551.
    [40] Heiko Hirschmüller,Peter R Innocent,Jon Garibaldi. Real-time correlation-basedstereo vision with reduced border errors[J]. International Journal of Computer Vision.2002,47(1-3):229-246.
    [41] Dorin Comaniciu, Peter Meer. Mean shift: A robust approach toward feature spaceanalysis[J].Pattern Analysis and Machine Intelligence, IEEE Transactions.2002,24(5):603-619.
    [42] Kuk-Jin Yoon, In So Kweon. Adaptive support-weight approach for correspondencesearch[J]. Pattern Analysis and Machine Intelligence, IEEE Transactions.2006,28(4):650-656.
    [43] Federico Tombari, Stefano Mattoccia, Luigi Di Stefano et al. Near real-time stereobased on effective cost aggregation[C], Pattern Recognition,2008. ICPR2008.19thInternational Conference.2008:1-4.
    [44] Nafise Barzigar, Aminmohammad Roozgard, Samuel Cheng et al. SCoBeP: Denseimage registration using sparse coding and belief propagation[J]. Journal of VisualCommunication and Image Representation.2012.
    [45] Frederic Besse, Carsten Rother, Andrew W Fitzgibbon et al. PMBP: PatchMatchBelief Propagation for Correspondence Field Estimation[C], BMVC,2012:1-11.
    [46] Xiaozhou Zhou, Pierre Boulanger. Radiometric invariant stereo matching based onrelative gradients[C], Image Processing (ICIP),201219th IEEE InternationalConference,2012:2989-2992.
    [47] Xiaozhou Zhou, Pierre Boulanger. New eye contact correction using radial basisfunction for wide baseline videoconference system[C]. Springer,2012:68-79.
    [48] Xing Mei, Xun Sun, Weiming Dong et al. Segment-Tree based Cost Aggregation forStereo Matching[C], Proceedings of the2013IEEE Conference on Computer Visionand Pattern Recognition,2013:313-320.
    [49] Cagatay Undeger, Faruk Polat. Real-time edge follow: A real-time path searchapproach[J]. Systems, Man, and Cybernetics, Part C: Applications and Reviews,IEEE Transactions.2007,37(5):860-872.
    [50] Farrokh Janabi-Sharifi, William J Wilson. A fast approach for robot motionplanning[J]. Journal of Intelligent and Robotic Systems.1999,25(3):187-212.
    [51] Javier Minguez, Luis Montano. Nearness diagram (ND) navigation: collisionavoidance in troublesome scenarios[J]. Robotics and Automation, IEEE Transactionson.2004,20(1):45-59.
    [52] Javier Minguez, Luis Montano. Sensor-based robot motion generation in unknown,dynamic and troublesome scenarios[J]. Robotics and Autonomous Systems.2005,52(4):290-311.
    [53] Anthony Stentz, Martial Hebert. A complete navigation system for goal acquisitionin unknown environments[J]. Autonomous Robots.1995,2(2):127-145.
    [54] Tao Zhang, Yi Zhu, Jingyan Song. Real-time motion planning for mobile robots bymeans of artificial potential field method in unknown environment[J]. IndustrialRobot: An International Journal.2010,37(4):384-400.
    [55] Iwan Ulrich, Johann Borenstein. Vfh: local obstacle avoidance with look-aheadverification[C], Robotics and Automation,2000. Proceedings ICRA'00. IEEEInternational Conference on,2000:2505-2511.
    [56] Camilo Ordonez, Emmanuel G Collins Jr, Majura F Selekwa et al. The virtual wallapproach to limit cycle avoidance for unmanned ground vehicles[J]. Robotics andAutonomous Systems.2008,56(8):645-657.
    [57] Omid Reza Esmaeili Motlagh, Tang Sai Hong, Napsiah Ismail. Development of anew minimum avoidance system for a behavior-based mobile robot[J]. Fuzzy setsand systems.2009,160(13):1929-1946.
    [58] Elon Rimon, Daniel E Koditschek. Exact robot navigation using artificial potentialfunctions[J]. Robotics and Automation, IEEE Transactions on.1992,8(5):501-518.
    [59] Shuzhi Sam Ge, Yan Juan Cui. New potential functions for mobile robot pathplanning[J]. Robotics and Automation, IEEE Transactions on2000,16(5):615-620.
    [60] Dong Hun Kim.Escaping route method for a trap situation in local path planning[J].International Journal of Control, Automation and Systems.2009,7(3):495-500.
    [61] Richard Volpe, Pradeep Khosla. Manipulator control with superquadric artificialpotential functions: Theory and experiments[J]. Systems, Man and Cybernetics,IEEE Transactions on.1990,20(6):1423-1436.
    [62] Ján Va ák. Navigation of mobile robots using potential fields and computationalintelligence means[J]. Acta Polytechnica Hungarica.2007,4(1):63-74.
    [63] WangBao Xu, XueBo Chen. Artificial moment method for swarm robot formationcontrol[J]. Science in China Series F: Information Sciences.2008,51(10):1521-1531.
    [64] Michael Weir, Anthony Buck, Jon Lewis. Potbug: A mind’ s eye approach toproviding bug-like guarantees for adaptive obstacle navigation using dynamicpotential fields[C]. Springer,2006:239-250.
    [65] Min Gyu Park, Min Cheol Lee, Kwon Son. Real-time path planning in unknownenvironments using a virtual hill[C],16th IFAC congress, Prague, Czech,2005.
    [66] Min Gyu Park, Min Cheol Lee. A new technique to escape local minimum inartificial potential field based path planning[J]. KSME international journal.2003,17(12):1876-1885.
    [67] Graeme Bell, Michael Weir. Forward chaining for robot and agent navigation usingpotential fields[C], Proceedings of the27th Australasian conference on Computerscience-Volume26,2004:265-274.
    [68] Xiaoping Yun, Ko-Cheng Tan. A wall-following method for escaping local minimain potential field based motion planning[C], Advanced Robotics,1997. ICAR'97.Proceedings8th International Conference on Automation and Robotics,1997:421-426.
    [69] James Ng, Thomas Br unl. Performance comparison of bug navigation algorithms[J].Journal of Intelligent and Robotic Systems.2007,50(1):73-84.
    [70] Mohamed M Mabrouk, Colin R McInnes. An emergent wall following behaviour toescape local minima for swarms of agents[J]. International Journal of ComputerScience.2008,35(4): IJCS-35.
    [71] Javier Antich,Alberto Ortiz,Javier Mínguez. A bug-inspired algorithm forefficient anytime path planning[C], Intelligent Robots and Systems,2009. IROS2009. IEEE/RSJ International Conference on,2009:5407-5413.
    [72] Yi Zhu, Tao Zhang, Jingyan Song et al. A new bug-type navigation algorithm formobile robots in unknown environments containing moving obstacles[J]. IndustrialRobot: An International Journal.2012,39(1):27-39.
    [73] Jie Zhao, Shuchun Yu, Hegao Cai. A precise method for correcting stereo pairscollected by a new binocular device[J]. Industrial Robot: An International Journal.2007,34(6):512-519.
    [74]于舒春,朱延河,闫继宏等.基于新型双目机构的立体视觉系统标定[J].机器人.2007,29(4):353-356,362.
    [75] C BRowN DUANE. Close-range camera calibration[J]. Photogrammetricengineering.1971,37(8):855-866.
    [76] John G Fryer, Duane C Brown. Lens distortion for close-rangephotogrammetry[J].Photogrammetric engineering and remote sensing.1986,52(1):51-58.
    [77] Quan-Tuan Luong, Olivier D Faugeras. The fundamental matrix: Theory, algorithms,and stability analysis[J].International Journal of Computer Vision.1996,17(1):43-75.
    [78] Thomas S. Huang, Olivier D. Faugeras. Some properties of th matrix in two-viewmotion estimation[J]. Pattern Analysis and Machine Intelligence, IEEE Transactionson.1989,11(12):1310-1312.
    [79] HC Longuet-Higgins. A computer algorithm for reconstructing a scene from twoprojections[J]. Readings in Computer Vision: Issues, Problems, Principles, andParadigms, MA Fischler and O. Firschein, eds.1987,61-62.
    [80] Richard Hartley, Andrew Zisserman.Multiple view geometry in computervision[M]: Cambridge Univ Press,2000.
    [81] Lazaros Nalpantidis, Antonios Gasteratos. Stereo vision for robotic applications inthe presence of non-ideal lighting conditions[J].Image and Vision Computing.2010,28(6):940-951.
    [82] Carl D Crane III, David G Armstrong II, Maryum Ahmed et al. Development of anintegrated sensor system for obstacle detection and terrain evaluation for applicationto unmanned ground vehicles[C], Defense and Security,2005:156-165.
    [83] U Grenander. Tutorials in Pattern synthesis[J]. Brown University, Division ofApplied Mathematics.1983,.
    [84] Donald Geman, Stuart Geman, Christine Graffigne et al. Boundary detection byconstrained optimization[J]. Pattern Analysis and Machine Intelligence, IEEETransactions on.1990,12(7):609-628.
    [85] Donald Geman, Basilis Gidas. Image analysis and computer vision[J]. Spatialstatistics and digital image analysis.1991,9-36.
    [86] Basilis Gidas. A renormalization group approach to image processing problems[J].Pattern Analysis and Machine Intelligence, IEEE Transactions on.1989,11(2):164-180.
    [87] Stan Z Li. Markov random field modeling in computer vision[M]: Springer-VerlagNew York, Inc,1995.
    [88] Stan Z Li. MAP image restoration and segmentation by constrained optimization[J].Image Processing, IEEE Transactions on.1998,7(12):1730-1735.
    [89] Stan Z Li. Roof-edge preserving image smoothing based on MRFs[J]. ImageProcessing, IEEE Transactions on.2000,9(6):1134-1138.
    [90] Stuart Geman, Donald Geman. Stochastic relaxation, Gibbs distributions, and theBayesian restoration of images[J]. Pattern Analysis and Machine Intelligence,IEEE Transactions on.1984,6):721-741.
    [91] Leonid I Rudin, Stanley Osher, Emad Fatemi. Nonlinear total variation based noiseremoval algorithms[J], Physica D: Nonlinear Phenomena.1992,60(1):259-268.
    [92] Julian Besag. On the statistical analysis of dirty pictures[J]. Journal of the RoyalStatistical Society. Series B (Methodological).1986,259-302.
    [93] Michael Steinbrunn, Guido Moerkotte, Alfons Kemper. Heuristic and randomizedoptimization for the join ordering problem[J]. The VLDB Journal—TheInternational Journal on Very Large Data Bases.1997,6(3):191-208.
    [94] Pierre Asselin, Richard Francis L Evans, Joe Barker et al. Constrained Monte Carlomethod and calculation of the temperature dependence of magnetic anisotropy[J].Physical Review B.2010,82(5):054415.
    [95] Huawu Deng, David A Clausi. Unsupervised image segmentation using a simpleMRF model with a new implementation scheme[J]. Pattern recognition.2004,37(12):2323-2335.
    [96] Brian Johnson, Zhixiao Xie. Unsupervised image segmentation evaluation andrefinement using a multi-scale approach[J]. ISPRS Journal of Photogrammetry andRemote Sensing.2011,66(4):473-483.
    [97] Todd E Zickler, Peter N Belhumeur, David J Kriegman. Helmholtz stereopsis:Exploiting reciprocity for surface reconstruction[J]. International Journal ofComputer Vision.2002,49(2-3):215-227.
    [98] Liang Wang, Miao Liao, Minglun Gong et al.High-quality real-time stereo usingadaptive cost aggregation and dynamic programming[C],3D Data Processing,Visualization, and Transmission, Third International Symposium on,2006:798-805.
    [99] David Marr, Ellen Hildreth. Theory of edge detection[J]. Proceedings of the RoyalSociety of London. Series B. Biological Sciencess.1980,207(1167):187-217.
    [100] Tony Lindeberg. Edge detection and ridge detection with automatic scaleselection[J]. International Journal of Computer Vision.1998,30(2):117-156.
    [101] John Canny. A computational approach to edge detection[J]. Pattern Analysisand Machine Intelligence, IEEE Transactions on.1986,6):679-698.
    [102] Cai-Xia Deng,Gui-Bin Wang,Xin-Rui Yang. Image edge detection algorithmbased on improved Canny operator[C], Wavelet Analysis and Pattern Recognition(ICWAPR),IEEE Conference on,2013,964-967
    [103] Jesper Moller. Markov chain Monte Carlo and spatial point processes1999.
    [104] Qingxiong Yang, Ruigang Yang, James Davis et al. Spatial-depth superresolution for range images[C], Computer Vision and Pattern Recognition,2007.CVPR'07. IEEE Conference on,2007:1-8.
    [105] Yuri Boykov, Vladimir Kolmogorov. An experimental comparison of min-cut/max-flow algorithms for energy minimization in vision[J]. Pattern Analysis andMachine Intelligence, IEEE Transactions on.2004,26(9):1124-1137.
    [106] Stan Z Li. Markov random field modeling in image analysis[M]: Springer,2009.
    [107] Julian Besag, Peter Green, David Higdon et al. Bayesian computation andstochastic systems[J]. Statistical Science.1995,3-41.
    [108] Richard Szeliski, Ramin Zabih, Daniel Scharstein et al.A comparative study ofenergy minimization methods for markov random fields with smoothness-basedpriors[J]. Pattern Analysis and Machine Intelligence, IEEE Transactions on.2008,30(6):1068-1080.
    [109] Renfrey Burnard Potts. Some generalized order-disorder transformations[C],Proceedings of the Cambridge Philosophical Society,1952:106-109.
    [110] Yuri Boykov, Olga Veksler, Ramin Zabih. Fast approximate energyminimization via graph cuts[J]. Pattern Analysis and Machine Intelligence, IEEETransactions on.2001,23(11):1222-1239.
    [111] Vladimir Kolmogorov. Graph based algorithms for scene reconstruction fromtwo or more views[D]: Citeseer,2004.
    [112] Tina Toni, David Welch, Natalja Strelkowa et al. Approximate Bayesiancomputation scheme for parameter inference and model selection in dynamicalsystems[J]. Journal of the Royal Society Interface.2009,6(31):187-202.
    [113] Andreas Geiger, Martin Roser, Raquel Urtasun. Efficient large-scale stereomatching[C]. Springer,2011:25-38.
    [114] Sébastien Roy. Stereo without epipolar lines: A maximum-flowformulation[J].International Journal of Computer Vision.1999,34(2-3):147-161.
    [115] DR Ford, Delbert Ray Fulkerson. Flows in networks[M]: Princeton universitypress,2010.
    [116] Russell C Eberhart, Yuhui Shi. Comparison between genetic algorithms andparticle swarm optimization[C], Evolutionary Programming VII,1998:611-616.
    [117] Alexander Schrijver. Combinatorial optimization: polyhedra and efficiency[M]:Springer,2003.
    [118] Yuri Boykov, Olga Veksler, Ramin Zabih. Markov random fields with efficientapproximations[C], Computer vision and pattern recognition,1998. Proceedings.1998IEEE computer society conference on,1998:648-655.
    [119] Vladimir Kolmogorov, Ramin Zabih. Multi-camera scene reconstruction viagraph cuts[C]. Springer,2002:82-96.
    [120] Vladimir Kolmogorov, Ramin Zabin. What energy functions can be minimizedvia graph cuts[J]. Pattern Analysis and Machine Intelligence, IEEE Transactions on.2004,26(2):147-159.
    [121] Vladimir Kolmogorov, Martin Wainwright. On the optimality of tree-reweightedmax-product message-passing[J]. Xiv preprint Xiv:1207.1395.2012,.
    [122] Tony Lindeberg.Scale-space theory in computer vision[M]: Springer,1993.
    [123] Paul T. Jackway, Mohamed Deriche. Scale-space properties of the multiscalemorphological dilation-erosion[J]. Pattern Analysis and Machine Intelligence, IEEETransactions on.1996,18(1):38-51.
    [124] Luc MJ Florack, Bart M ter Haar Romeny,Jan J Koenderink et al. Scale and thedifferential structure of images[J]. Image and Vision Computing.1992,10(6):376-388.
    [125] David G Lowe. Object recognition from local scale-invariantfeatures[C],Computer vision,1999. The proceedings of the seventh IEEEinternational conference on,1999:1150-1157.
    [126] David G Lowe. Distinctive image features from scale-invariant keypoints[J].International Journal of Computer Vision.2004,60(2):91-110.
    [127] Herbert Bay, Andreas Ess, Tinne Tuytelaars et al. Speeded-up robust features(SURF)[J]. Computer vision and image understanding.2008,110(3):346-359.
    [128] Herbert Bay, Tinne Tuytelaars, Luc Van Gool. Surf: Speeded up robustfeatures[C]. Springer,2006:404-417.
    [129] Paul Viola, Michael Jones. Rapid object detection using a boosted cascade ofsimple features[C], Computer Vision and Pattern Recognition,2001. CVPR2001.Proceedings of the2001IEEE Computer Society Conference on,2001: I-511-I-518vol.511.
    [130] Michael Grabner, Helmut Grabner, Horst Bischof. Fast approximated SIFT[C].Springer,2006:918-927.
    [131] Yan Ke, Rahul Sukthankar. PCA-SIFT: A more distinctive representation forlocal image descriptors[C], Computer Vision and Pattern Recognition,2004. CVPR2004. Proceedings of the2004IEEE Computer Society Conference on,2004:II-506-II-513Vol.502.
    [132] Minh N Do, Martin Vetterli. The contourlet transform: an efficient directionalmultiresolution image representation[J]. Image Processing, IEEE Transactions on,2005,14(12):2091-2106.
    [133]汪剑鸣,王曦,王胜蓓等.室内惯性/视觉组合导航地面图像分割算法[J].中国惯性技术学报.2011,19(5):553-558.
    [134] Dominik Belter, Piotr Skrzypczynski. Integrated motion planning for a hexapodrobot walking on rough terrain[C],18th IFAC World Congress,2011:6918-6923.
    [135] Viet Pham, Carl Laird, Mahmoud El-Halwagi. Convex hull discretizationapproach to the global optimization of pooling problems[J]. Industrial&EngineeringChemistry Research.2009,48(4):1973-1979.
    [136] Ronald L Graham, F Frances Yao. Finding the convex hull of a simplepolygon[J]. Journal of Algorithms.1983,4(4):324-331.
    [137] Edsger W Dijkstra. Solution of a problem in concurrent programming control[C].Springer,2001:289-294.
    [138]陈甫,臧希喆,闫继宏等.适合航行的六足仿生机器人Spider的研制[J].吉林大学学报:工学版.2011,41(3):765-770.
    [139]陈甫,臧希喆,赵杰等.六足步行机器人仿生机制研究[J].机械与电子.2009:9-016.
    [140]罗庆生,韩宝玲.现代仿生机器人设计[M]:电子工业出版社,2008.
    [141]刘海清,刘玉斌,张赫等.仿生六足机器人基于足力分布的位姿调整策略[J].哈尔滨商业大学学报:自然科学版.2012,28(5):541-545.
    [142]赵杰,张赫,刘玉斌等.六足机器人HITCR-I的研制及步行实验[J].华南理工大学学报,自然科学版.2012,40(12).
    [143] Pedro F, Felzenszwalb. Efficient Belief Propagation for Early Vision[J],International Journal of Computer Vision.2006,70(1),41–54.
    [144] Rabiner LR. A tutorial on hidden Markov models and selected applications inspeech recognition,1989, Proceedings of the IEEE(2):257-286.