Rossum--tpofinder 平面纹理物体识别

一开始是打算用Roboearth来做物体识别的,但是折腾了一段时间觉得自己做训练物体模型实在是很麻烦,识别的效果感觉也不太好。然后搜了其它的可以用于物体识别的库,包括ROS里的object_recognitionPartsBasedDetector还有OpenTLD等等,发现这些东西很多文档都不全,配置也很麻烦,我用不来。

然后我发现了tpofinder,这仍然是一个用二维图像来做物体识别的库,这句话说得很好,"in the robot challenge, we required software that is quickly installed, compiled, and integrated. "。tpofinder用起来非常简单,只需要一张物体的图片用作训练,不过由于依靠的是物体的平面纹理,对书本封面,咖啡盒之类的东西识别效果比较好,如果是没有什么纹理特征的东西就不行了。据那篇文章说,"it is a bag-of-features approach, where the test images and the models are described by local features that are somewhat robust towards scale, rotation and change in illumination. ",看了一下源代码,发现它主要用的应该是ORB特征,包含在OpenCV 2.3以后的版本中,这个特征是Willow Garage做的,比sift和surf还给力。

实际到了我来做物体识别的时候我们已经没有多少时间和精力了,要准备期末考和考研。原本我的想法是用cvblob把物体的运动轨迹做出来,然后根据运动轨迹来做很多有意思的事情,可惜时间有限,我们的项目也马上结题了。最后只是简单地调用了一下tpofinder识别出几个物体,然后算出轮廓矩计算中心位置,让舵机粗略对正物体,仅仅做到这一步。没有用上ROS OpenCV的cv_bridge接口的原因是图像无法处理,却又不报错,但是我用OpenCV最简单的画圈函数在图像上花个圈却没有问题,不明原因。折腾好久之后终于放弃,只能用OpenCV的接口采集图像处理显示。所以这一部分的代码基本对tpofinder没有什么改动,增加的仅仅是发送消息到rostopic来控制舵机。其实还想加上语音问询,然后用ROS OpenCV的接口让它可以在rviz里显示的,然后再用Qt做一个训练过程的图形界面,但是都没有时间了。

这是舵机控制的主要代码:

    while (ros::ok()) {
        nextImage();
        if (iCount >= 15){
            processImage(detector);
            iCount = 0;
        }

        if(!foundFlag){
            if (iServoCount == 40){
                joint_msg.header.stamp = ros::Time::now();
                joint_msg.name[0] = "pan";
                joint_msg.name[1] = "tilz";
                joint_msg.velocity[0] = 0.7;
                joint_msg.velocity[1] = 0.7;
                joint_msg.position[0] = 0.055;
                joint_msg.position[1] = 0.7;
                ServoArea = 0.055;
                servo_pub.publish(joint_msg);
            } else if (iServoCount == 80){
                joint_msg.header.stamp = ros::Time::now();
                joint_msg.name[0] = "pan";
                joint_msg.name[1] = "tilz";
                joint_msg.velocity[0] = 0.7;
                joint_msg.velocity[1] = 0.7;
                joint_msg.position[0] = -0.320;
                joint_msg.position[1] = 0.7;
                ServoArea = -0.320;
                servo_pub.publish(joint_msg);
            } else if (iServoCount == 120){
                joint_msg.header.stamp = ros::Time::now();
                joint_msg.name[0] = "pan";
                joint_msg.name[1] = "tilz";
                joint_msg.velocity[0] = 0.7;
                joint_msg.velocity[1] = 0.7;
                joint_msg.position[0] = -0.695;
                joint_msg.position[1] = 0.7;
                ServoArea = -0.695;
                servo_pub.publish(joint_msg);
                iServoCount = 0;
            } 
        } 

        if(foundFlag) {
            joint_msg.header.stamp = ros::Time::now();
            joint_msg.name[0] = "pan";
            joint_msg.name[1] = "tilz";
            joint_msg.velocity[0] = 0.5;
            joint_msg.velocity[1] = 0.5;
            joint_msg.position[1] = 0.7;

            if (centerPoint.x < 213){
                joint_msg.position[0] = ServoArea+(-0.375)*0.25;
            } else if (centerPoint.x >= 213 && centerPoint.x <= 426){
                joint_msg.position[0] = ServoArea+(-0.375)*0.5;
            } else if (centerPoint.x > 426)
                joint_msg.position[0] = ServoArea+(-0.375)*0.75;

            if ( iServoCount >= 0 ){
                servo_pub.publish(joint_msg); 
                iServoCount = 0;
            }
        }


  • 0
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值