完整代码:
mkdir rosimgsend
cd rosimgsend
mkdir src
catkin_make -DPYTHON_EXECUTABLE=/usr/bin/python3
cd src
catkin_create_pkg pub_sub_eg roscpp std_msgs image_transport cv_bridge
cd pub_sub_eg
cd src
gedit pub.cpp
gedit sub.cpp
cd ..
gedit CMakeLists.txt
cd ..
cd ..
catkin_make -DPYTHON_EXECUTABLE=/usr/bin/python3
cd devel/lib/pub_sub_eg
./pub
./sub
具体思路:
- 建立空文件夹rosimgsend和手动建立src
- catkin_make 建立需要的ros各种东西 最好指定python版本
- 到src中
- 使用catkin_create_pkg指令,建立一个pub_sub_eg的程序,并关联ros的各种包
- pub_sub_eg里面有2个文件,2个文件夹
- 在src中,放入cpp
- 修改CMakeList,把cpp链接进去,并把需要使用的额外库,比如opencv也导入
- 最后回到rosimgsend,再次catkin_make,这时会自动解析自己定义的pub_sub_eg(因为使用catkin_create_pkg建立的,系统可以自动识别)
- 最后,会在devel中生成一大堆文件,在lib中有最终我们可以执行的文件
图片解析:
进入src
在cmakelist中加入代码:
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS} )
add_executable(${PROJECT_NAME}_talker src/pub_eg.cpp)
add_executable(${PROJECT_NAME}_listener src/sub_eg.cpp)
target_link_libraries(${PROJECT_NAME}_listener ${catkin_LIBRARIES} ${OpenCV_LIBS})
target_link_libraries(${PROJECT_NAME}_talker ${catkin_LIBRARIES} ${OpenCV_LIBS})
接着,打开roscore,分别建立终端,调用listener和talker
pub.cpp
//pub_eg.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "sensor_msgs/Imu.h"
#include "sensor_msgs/NavSatFix.h"
#include "sensor_msgs/Image.h"
#include <sstream>
#include <string>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/opencv.hpp>
#include <iostream>
#include <sys/stat.h>
#include <cstring>
#include <string>
#include <stdlib.h>
#include <stdio.h>
#include <dirent.h>
#include <vector>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
using namespace std;
using namespace cv;
int main(int argc, char **argv) {
ros::init(argc, argv, "cam_node");
int video_device;
int frame_rate;
ros::NodeHandle nh("~");
image_transport::ImageTransport it(nh);
image_transport::Publisher pub = it.advertise("image_raw", 10);
ROS_INFO("Camera device%d openned, fps=%d", video_device, frame_rate);
while(1){
cv::Mat image =imread("/home/xxx/Documents/catkin_sw/src/hello_world/src/opencv-logo.jpeg",IMREAD_COLOR);
cout<<image.size().width<<endl;
cv_bridge::CvImage out_msg;
out_msg.header.stamp = ros::Time::now();
out_msg.encoding = sensor_msgs::image_encodings::RGB8;
out_msg.image = image;
pub.publish(out_msg.toImageMsg());
std::cout<<"img loop"<<std::endl;
}
return 0;
}
sub.cpp
//sub_eg.cpp
#include "ros/ros.h"
#include <sensor_msgs/Imu.h>
#include "std_msgs/String.h"
#include "sensor_msgs/NavSatFix.h"
#include "sensor_msgs/Image.h"
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/opencv.hpp>
#include <string>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
using namespace std;
void imageCb(const sensor_msgs::ImagePtr& msg)
{
std::cout<<"imageCb"<<std::endl;
cv_bridge::CvImagePtr cv_ptr;
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8);
cout<<"width is "<<cv_ptr->image.size().width<<endl;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "cam_parse");
ros::NodeHandle nh("~");
std::cout<<"subcriber!!!!"<<std::endl;
image_transport::ImageTransport it(nh);
ros::Subscriber imusub = nh.subscribe("/cam_node/image_raw", 10, imageCb);
ros::spin();
return 0;
}
src目录结构