创建指定OpenCV版本的ROS工程
一、创建工作空间和程序包
mkdir -p ~/catkin_cv/src
cd catkin_cv/
catkin_make
source devel/setup.sh
cd src
catkin_create_pkg ballseeker roscpp rospy std_msgs sensor_msgs cv_bridge image_transport dynamic_reconfigure
二、创建并且编写cpp文件与hpp文件
gedit ballseeker/include/ballseeker/seek.hpp
gedit ballseeker/src/seek.cpp
gedit ballseeker/src/seekernode.cpp
#代码见附录
三、修改CMakeLists.txt
在CMakeLists最后加上:
# catkin_add_nosetests(test)
set(OpenCV_DIR /usr/local/share/OpenCV4)
find_package(OpenCV REQUIRED)
add_library(${PROJECT_NAME} src/seek.cpp)
add_dependencies(
${PROJECT_NAME}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(
${PROJECT_NAME}
${catkin_LIBRARIES}
)
#add the publisher example
add_executable(seekernode src/seek.cpp include/ballseeker/seek.hpp src/seekernode.cpp)
target_link_libraries(seekernode ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
四、编译与运行
cd catkin_cv/
source ~/catkin_cv/devel/setup.sh
catkin_make
#新开一个终端运行:
roscore
#再回之前的终端运行:
rosrun ballseeker seekernode
五、编写launch文件快速启动
在终端中运行:
cd ~/catkin_cv/src/ballseeker/launch
gedit quickstart.launch
在quickstart.launch中写入:
<launch>
<node
pkg= "ballseeker"
name="quickseeknode"
type="seekernode"
/>
</launch>
回到终端再运行:
source ~/catkin_cv/devel/setup.sh
roslaunch ballseeker quickstart.launch
六、dynamic_reconfigure
略
七、调整与保存参数
略
八、附录(示例代码)
这里的代码的作用是调用摄像头来检测它看到的网球
在seek.hpp中写入:
#pragma once
#include "ros/ros.h"
#include "opencv2/opencv.hpp"
#include "vector"
#include "sstream"
const int red_ball = 0;
const int yellow_ball = 1;
const int blue_ball = 2;
class seek
{
public:
seek(int service_id=0);
~seek();
void getstart(); //从摄像头获取图片、双边滤波、转化hsv
void display(); //找球并展示中间效果和最终效果
void creatbar(); //创建滑动条调整参数
private:
int bgr_min[3];
int bgr_max[3];
int hsv_min[3];
int hsv_max[3];
cv::Mat src;
cv::Mat bgr_dst;
cv::Mat hsv_dst;
cv::Mat see_red;
cv::Mat see_yellow;
cv::Mat see_blue;
cv::VideoCapture capture;
void updateparam(int type_of_ball);
void process(cv::Mat& input,int type_of_ball);//阈值化、膨胀、找轮廓、找矩形并筛选、画圆
static void on_change(int, void*);
};
在seek.cpp中写入:
#include "../include/ballseeker/seek.hpp"
seek::seek(int service_id)
{
//设置摄像机参数
capture.open(1);
capture.set(CV_CAP_PROP_FRAME_WIDTH,640);
capture.set(CV_CAP_PROP_FRAME_HEIGHT,480);
}
seek::~seek()
{
}
void seek::getstart()
{
capture>>src;
cv::bilateralFilter(src,bgr_dst,20,1000,1000);
cv::cvtColor(bgr_dst,hsv_dst,CV_BGR2HSV);
}
void seek::display()
{
process(see_red,red_ball); //可能得会用bgr处理红球了,HSV下效果不太好
process(see_yellow,yellow_ball);
process(see_blue,blue_ball);
cv::imshow("SEE_RED_BALL",see_red);
cv::imshow("SEE_YELLOW_BALL",see_yellow);
cv::imshow("SEE_BLUE_BALL",see_blue);
cv::imshow("FINALLY",src);
cv::waitKey(30);
}
void seek::process(cv::Mat& input, int type_of_ball)
{
updateparam(type_of_ball);
cv::inRange(hsv_dst,cv::Scalar(hsv_min[0],hsv_min[1],hsv_min[2]),
cv::Scalar(hsv_max[0],hsv_max[1],hsv_max[2]),input);
cv::Mat element =cv::getStructuringElement(cv::MORPH_RECT, cv::Size(15, 15));
cv::dilate(input, input, element);
std::vector<std::vector<cv::Point> > contours;
std::vector<cv::Vec4i> hierarchy;
std::vector<cv::Rect> rects;
cv::findContours(input, contours, hierarchy, cv::RETR_CCOMP, cv::CHAIN_APPROX_SIMPLE);
for (int i = 0; i < contours.size(); i++)
{
rects.push_back(cv::boundingRect(contours[i]));
if ((rects.back().height < 100 || rects.back().width < 100) ||
fabsf(rects.back().height - rects.back().width) > 20)
rects.erase(rects.end() - 1);
}
for (int i = 0; i < rects.size(); i++)
{
double R = (rects[i].height + rects[i].width) / 4;
double x = rects[i].x + R;
double y = rects[i].y + R;
cv::Point center(x, y);
cv::circle(src, center, R + 5, cv::Scalar(0, 0, 255), 5);
}
}
void seek::updateparam(int type_of_ball)
{
switch (type_of_ball)
{
case red_ball:
hsv_min[0]= 0 ;hsv_min[1]= 105 ;hsv_min[2]= 108 ;
hsv_max[0]= 11 ;hsv_max[1]= 255 ;hsv_max[1]= 255 ;
break;
case yellow_ball:
hsv_min[0]= 18 ;hsv_min[1]= 56 ;hsv_min[2]= 177 ;
hsv_max[0]= 71 ;hsv_max[1]= 187 ;hsv_max[1]= 255 ;
break;
case blue_ball:
hsv_min[0]= 85 ;hsv_min[1]= 129 ;hsv_min[2]= 128 ;
hsv_max[0]= 124 ;hsv_max[1]= 255 ;hsv_max[1]= 255 ;
break;
default:
break;
}
}
void seek::creatbar()
{
cv::namedWindow("SetParam");
cv::createTrackbar("minH", "SetParam", &hsv_min[0], 180, on_change);
cv::createTrackbar("minS", "SetParam", &hsv_min[1], 255, on_change);
cv::createTrackbar("minV", "SetParam", &hsv_min[2], 255, on_change);
cv::createTrackbar("maxH", "SetParam", &hsv_max[0], 180, on_change);
cv::createTrackbar("maxS", "SetParam", &hsv_max[1], 255, on_change);
cv::createTrackbar("maxV", "SetParam", &hsv_max[2], 255, on_change);
on_change(0, 0);
}
void seek::on_change(int, void*)
{
}
在seekernode.cpp中写入:
#include "../include/ballseeker/seek.hpp"
int main(int argc,char** argv)
{
ros::init(argc,argv,"seekernode");
ros::NodeHandle n;
seek icu(1);
icu.creatbar();
while(ros::ok())
{
icu.getstart();
icu.display();
ros::spinOnce();
}
return 0;
}