使用rosserial实现ROS与Windows的service服务通信

小结

使用rosserial window来实现ROS与Windows的service服务通信,测试了add_two_ints的服务,并使用rosserial window在windows端创建Visual Studio C++连接使用创建的add_two_ints服务,并测试成功。

回顾:rosserial windows实现rostopic的发布和订阅

使用rosserial windows实现rostopic的发布和订阅的资料容易得到,网上有现成的,参见 https://github.com/Waywrong/ros_win_msg/tree/master/RosserialWin

http://wiki.ros.org/rosserial_windows

Rosserial Windows Client C++代码经过测试如下:

int main()
{
    std::cout << "Hello World!\n";
	ros::NodeHandle nh;

	char *ros_master = "192.168.86.28";// 运行rosseial服务器节点的主机IP

	printf("Connecting to server at %s\n", ros_master);
	nh.initNode(ros_master);

	printf("Advertising cmd_vel message\n");

	geometry_msgs::Twist twist_msg;

	ros::Publisher cmd_vel_pub("/turtle1/cmd_vel", &twist_msg);
	nh.advertise(cmd_vel_pub);

	printf("Go robot go!\n");

	while (1)
	{
		twist_msg.linear.x = 5.1;
		twist_msg.linear.y = 0;
		twist_msg.linear.z = 0;
		twist_msg.angular.x = 0;
		twist_msg.angular.y = 0;
		twist_msg.angular.z = -1.8;
		cmd_vel_pub.publish(&twist_msg);
		nh.spinOnce();
		Sleep(100);
	}

	printf("All done!\n");
	system("pause");
	return 0;
}

正题: 使用rosserial实现ROS与Windows的service服务通信

启动roscore

john@ubuntu:~$ roscore
... logging to /home/john/.ros/log/8ba9ec9a-10da-11ed-ad09-9d6885123387/roslaunch-ubuntu-6888.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://ubuntu:33213/
ros_comm version 1.15.14


SUMMARY
========

PARAMETERS
 * /rosdistro: noetic
 * /rosversion: 1.15.14

NODES

auto-starting new master
process[master]: started with pid [6900]
ROS_MASTER_URI=http://ubuntu:11311/

setting /run_id to 8ba9ec9a-10da-11ed-ad09-9d6885123387
process[rosout-1]: started with pid [6911]
started core service [/rosout]

启动add_two_ints的服务并测试

启动add_two_ints的服务:

john@ubuntu:~$ rosrun ros_cpp add_two_ints_server.py 
Ready to add two ints.

有以下服务:

john@ubuntu:~$ rosservice list
/add_two_ints
/add_two_ints_server/get_loggers
/add_two_ints_server/set_logger_level
/rosout/get_loggers
/rosout/set_logger_level

在本机测试,返回成功的结果:

john@ubuntu:~$ rosrun ros_cpp add_two_ints_client.py 6 4
Requesting 6+4
6 + 4 = 10

服务端结果:

john@ubuntu:~$ rosrun ros_cpp add_two_ints_server.py 
Ready to add two ints.
Returning [6 + 4 = 10]

服务器与客户端的python代码如下:

  • add_two_ints_server.py

#!/usr/bin/env python
  
from ros_essentials_cpp.srv import AddTwoInts
from ros_essentials_cpp.srv import AddTwoIntsRequest
from ros_essentials_cpp.srv import AddTwoIntsResponse

import rospy

def handle_add_two_ints(req):
    print ("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
    return AddTwoIntsResponse(req.a + req.b)

def add_two_ints_server():
    rospy.init_node('add_two_ints_server')
    s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
    print ("Ready to add two ints.")
    rospy.spin()

if __name__ == "__main__":
    add_two_ints_server()
  • add_two_ints_client.py:
#!/usr/bin/env python

import sys
import rospy
from ros_essentials_cpp.srv import AddTwoInts
from ros_essentials_cpp.srv import AddTwoIntsRequest
from ros_essentials_cpp.srv import AddTwoIntsResponse

def add_two_ints_client(x, y):
    rospy.wait_for_service('add_two_ints')
    try:
        add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
        resp1 = add_two_ints(x, y)
        return resp1.sum
    except rospy.ServiceException(e):
        print ("Service call failed: %s"%e)

def usage():
    return

if __name__ == "__main__":
    if len(sys.argv) == 3:
        x = int(sys.argv[1])
        y = int(sys.argv[2])
    else:
        print ("%s [x y]"%sys.argv[0])
        sys.exit(1)
    print ("Requesting %s+%s"%(x, y))
    s = add_two_ints_client(x, y)
    print ("%s + %s = %s"%(x, y, s))

使用rosserial Windows client C++实现与ROS的add_two_ints service服务通信

参考关于如何利用rosserial在windows和linux间实现service服务 和 arduino的rosserial的实现: rosserial/rosserial_arduino/src/ros_lib/examples/ServiceClient/ServiceClient.pde

rosserial Windows client C++实现代码如下:

#include <iostream>
#include <string>
#include <stdio.h>
#include "ros.h"
#include <ros_essentials_cpp/AddTwoInts.h>
#include <windows.h>

ros::NodeHandle nh;
using ros_essentials_cpp::AddTwoInts;

ros::ServiceClient<ros_essentials_cpp::AddTwoInts::Request, ros_essentials_cpp::AddTwoInts::Response> client("add_two_ints");

ros_essentials_cpp::AddTwoInts::Request req;
ros_essentials_cpp::AddTwoInts::Response res;

int main(int argc, char ** argv)
{
	std::cout << "Hello World!\n";
	char *ros_master = "192.168.86.28";

	if (argc != 3)
	{
		printf("usage: add_two_ints_client X Y");
		return 1;
	}

	printf("Connecting to server at %s\n", ros_master);
	nh.initNode(ros_master);

	nh.serviceClient(client);

	while (!nh.connected())
	{
		nh.spinOnce();
		nh.loginfo("John is connected");	
	}

	req.a = atoll(argv[1]);
	req.b = atoll(argv[2]);
	
	client.call(req, res);
	printf("Sum: %ld", (long int)res.sum);
	return 0;

}

成功的测试结果

这里要启动rosserial_server

john@ubuntu:~$ rosrun rosserial_server socket_node
[ INFO] [1659280508.931238641]: Listening for rosserial TCP connections on port 11411

否则会报错:

Failed to receive data from server 10093
Send failed with error 10093
Failed to receive data from server 10093

rosserial Windows client C++客户端结果 (输入两个整数为5和20):

Hello World!
Connecting to server at 192.168.86.28
Sum: 25
D:\ROS_ServiceTest\Debug\ROS_ServiceTest.exe (process 20108) exited with code 0.
To automatically close the console when debugging stops, enable Tools->Options->Debugging->Automatically close the console when debugging stops.
Press any key to close this window . . .


服务器结果如下:

john@ubuntu:~$ rosrun ros_essentials_cpp add_server.py 
Ready to add two ints.
Returning [6 + 4 = 10]
Returning [5 + 20 = 25]

串口处输出如下:

john@ubuntu:~$ rosrun rosserial_server socket_node
[ INFO] [1659280508.931238641]: Listening for rosserial TCP connections on port 11411
[ INFO] [1659280566.121354532]: John is connected
[ INFO] [1659280566.122366251]: John is connected
[ INFO] [1659280566.123935089]: John is connected
[ INFO] [1659280566.125541004]: John is connected
[ INFO] [1659280566.125794801]: John is connected
......
......
[ WARN] [1659280570.507645794]: Socket asio error, closing socket: system:104


参考

关于如何利用rosserial在windows和linux间实现service服务
Rosserial-embeddedlinux部署
ROS串口编程学习笔记
root / quad2 / arduino / src / ros_lib / examples / ServiceClient / ServiceClient.pde @ c1426757
Github: rosserial/rosserial_arduino/src/ros_lib/examples/ServiceClient/ServiceClient.pde
https://github.com/Waywrong/ros_win_msg/tree/master/RosserialWin
http://wiki.ros.org/ROS/Tutorials/WritingServiceClient%28python%29
http://wiki.ros.org/rosserial_windows
https://answers.ros.org/question/299081/call-service-from-arduino/
https://answers.ros.org/question/263060/what-arguments-for-rospyserviceproxy/
https://atadiat.com/en/e-rosserial-arduino-introduction/

  • 0
    点赞
  • 6
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值