当前位置:网站首页>ROS之service传输图片
ROS之service传输图片
2022-07-31 05:16:00 【xp_fangfei】
之前一直用Topic来进行图片的传输,近期由于项目需要,需要用service进行图片的传输,查了不少博客很少有详细的解释,故写博客记录一下方便后续查询,也为了帮助大家。
topic和service对于图片的传输格式是一样的,只不过两者的通信方式不一样。
在此只介绍源码的编写,对于如何创建service工作空间,如何编译在我的上一篇博客中有详细的介绍。
srv文件
img.srv
sensor_msgs/Image image // 图像转换到sensor_msgs/Image格式进行传输
---
string a
string b
C++版本
ros和opencv之间图片如何传输详见:Converting between ROS images and OpenCV images (C++)
客户端程序
client_img.cpp
#include <ros/ros.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include "learn_service/img.h"
int main(int argc, char** argv)
{
ros::init(argc, argv, "client_img");
ros::NodeHandle node;
// 发现/cam服务后,创建一个服务客户端,连接名为/service_img的service
ros::service::waitForService("/cam");
ros::ServiceClient img_client = node.serviceClient<learn_service::img>("/cam");
//读取图片
cv::Mat image = cv::imread("../data/6.png");
sensor_msgs::ImagePtr image_srv = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg(); //图片转换成消息格式进行传输
// 初始化learn_service::img的请求数据
learn_service::img srv;
srv.request.image = *image_srv;
// 请求服务调用
img_client .call(srv);
// TO-DO: 处理服务调用结果
return 0;
};
服务端程序
server_img.cpp
#include <ros/ros.h>
#include "learn_service/img.h"
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
// service回调函数,输入参数req,输出参数res
bool cam_result_callback(learn_service::img::Request &req,
learn_service::img::Response &res)
{
cv_bridge::CvImagePtr cv_ptr;
//图像有消息格式转换成Mat格式
cv_ptr = cv_bridge::toCvCopy(req.image, sensor_msgs::image_encodings::BGR8);
cv::imshow("view", cv_ptr->image);
cv::waitKey(0);
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "server_img");
ros::NodeHandle node;
// 创建一个名为/cam的server,注册回调函数cam_result_callback
ros::ServiceServer img_service = node.advertiseService("/cam", cam_result_callback);
// 循环等待回调函数
ros::spin();
return 0;
}
python版本
ros和opencv之间图片如何传输详见:Converting between ROS images and OpenCV images (Python)
客户端程序
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
import sys
import rospy
import cv2
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
from learn_service.srv import img, imgRequest
def Img_client():
# ROS节点初始化
rospy.init_node('client_img')
# 发现/img服务后,创建一个服务客户端,连接名为/img的service
rospy.wait_for_service('/img')
bridge = CvBridge()
#读取图片
image = cv2.imread('/home/ubuntu/ros_practice/src/learn_service/data/6.png')
#转换图片为消息格式
image_message = bridge.cv2_to_imgmsg(image, "bgr8")
# try:
img_client = rospy.ServiceProxy('/img', img)
# 请求服务调用,输入请求数据
response = img_client(image_message)
return response.a
# except rospy.ServiceException, e:
# print "Service call failed: %s"%e
if __name__ == "__main__":
#服务调用并显示调用结果
Img_client()
服务端程序
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
import rospy
import cv2
from learn_service.srv import img, imgResponse
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
def ImgCallback(req):
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(req.image, "bgr8")
cv2.imshow("view", cv_image)
cv2.waitKey(0)
# 反馈数据
#return imgResponse("OK1", "OK2")
def img_server():
# ROS节点初始化
rospy.init_node('server_img')
# 创建一个名为/show_person的server,注册回调函数personCallback
s = rospy.Service('/img', img, ImgCallback)
# 循环等待回调函数
print("Ready to show img informtion")
rospy.spin()
if __name__ == "__main__":
img_server()
边栏推荐
- cv2.resize()是反的
- js中流程控制语句
- 动态规划(一)| 斐波那契数列和归递
- unicloud cloud development record
- js中的this指向与原型对象
- For penetration testing methods where the output point is a timestamp (take Oracle database as an example)
- understand js operators
- mysql常用命令
- UiBot has an open Microsoft Edge browser and cannot perform the installation
- js中的对象与函数的理解
猜你喜欢
计算图像数据集均值和方差
flutter arr dependencies
小米手机短信定位服务激活失败
js中的全局作用域与函数作用域
变分自编码器VAE实现MNIST数据集生成by Pytorch
VS connects to MYSQL through ODBC (1)
Take you to understand the MySQL isolation level, what happens when two transactions operate on the same row of data at the same time?
Notes on creating a new virtual machine in Hyper-V
腾讯云GPU桌面服务器驱动安装
npm WARN config global `--global`, `--local` are deprecated. Use `--location solution
随机推荐
深度学习知识点杂谈
Markdown help documentation
微信小程序启动优化
Multi-Modal Face Anti-Spoofing Based on Central Difference Networks学习笔记
cocos2d-x-3.2 image graying effect
Tencent Cloud Lightweight Server deletes all firewall rules
Take you to understand the MySQL isolation level, what happens when two transactions operate on the same row of data at the same time?
动态规划(一)| 斐波那契数列和归递
quick-3.5 ActionTimeline的setLastFrameCallFunc调用会崩溃问题
为什么bash中的read要配合while才能读取/dev/stdin的内容
cocos2d-x-3.2 Physics
jenkins +miniprogram-ci 一键上传微信小程序
this指向问题
Tencent Cloud GPU Desktop Server Driver Installation
Xiaomi mobile phone SMS location service activation failed
小米手机短信定位服务激活失败
js中的this指向与原型对象
configure:error no SDL library found
cocos2d-x-3.2 不能混合颜色修改
DC-CDN学习笔记