├── .gitignore ├── launch ├── udp_test.launch └── udp_rospy_test.launch ├── README.md ├── src ├── test_pub.py ├── udp_publisher.cpp └── udp_node.cpp ├── package.xml ├── CMakeLists.txt └── include └── udp_node.h /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | -------------------------------------------------------------------------------- /launch/udp_test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /launch/udp_rospy_test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # udp test 2 | 3 | ros中使用udp进行订阅的测试 4 | 5 | 在使用ROS进行通信的过程中。如果节点间采用有线网连接,网络可靠性高可以采用TCP传输协议。但是在使用wifi等无线网和机器人通信时,TCP连接不可靠经常会出现连接错误。此时采用UDP传输协议更为高效。 6 | 我们可以通过设置 `ros::TransportHints` 指定通信方式。 7 | 8 | 通过测试发现rospy发布的消息是无法支持UDP协议的。只有通过roscpp发布的消息才支持UDP协议。 9 | -------------------------------------------------------------------------------- /src/test_pub.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | from std_msgs.msg import String 5 | import time 6 | 7 | if __name__ == "__main__": 8 | rospy.init_node("rospy_udp_test") 9 | test_pub = rospy.Publisher("/chatter", String, queue_size=1) 10 | while not rospy.is_shutdown(): 11 | test_pub.publish("hello") 12 | rospy.loginfo("published: hello") 13 | time.sleep(1) 14 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | udp_test 3 | 0.0.1 4 | 5 | udp subscribe test 6 | 7 | MIT 8 | Randoms 9 | Randoms 10 | http://github.com/bluewhalerobot/udp_test 11 | https://github.com/bluewhalerobot/udp_test/issues 12 | https://github.com/bluewhalerobot/udp_test 13 | 14 | catkin 15 | message_runtime 16 | message_generation 17 | roscpp 18 | std_msgs 19 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(udp_test) 3 | 4 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 5 | 6 | find_package(catkin REQUIRED COMPONENTS 7 | roscpp 8 | std_msgs 9 | message_generation 10 | ) 11 | 12 | include_directories( 13 | ${catkin_INCLUDE_DIRS} 14 | ${PROJECT_SOURCE_DIR}/include 15 | ${PROJECT_SOURCE_DIR}/src 16 | ) 17 | 18 | catkin_package( 19 | CATKIN_DEPENDS roscpp std_msgs message_generation message_runtime 20 | ) 21 | 22 | add_executable(udp_node 23 | ${PROJECT_SOURCE_DIR}/src/udp_node.cpp 24 | ) 25 | 26 | add_executable(udp_pub_node 27 | ${PROJECT_SOURCE_DIR}/src/udp_publisher.cpp 28 | ) 29 | 30 | target_link_libraries(udp_node 31 | ${catkin_LIBRARIES} 32 | ) 33 | 34 | target_link_libraries(udp_pub_node 35 | ${catkin_LIBRARIES} 36 | ) -------------------------------------------------------------------------------- /include/udp_node.h: -------------------------------------------------------------------------------- 1 | /****************************************************************************** 2 | * 3 | * The MIT License (MIT) 4 | * 5 | * Copyright (c) 2018 Bluewhale Robot 6 | * 7 | * Permission is hereby granted, free of charge, to any person obtaining a copy 8 | * of this software and associated documentation files (the "Software"), to deal 9 | * in the Software without restriction, including without limitation the rights 10 | * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 11 | * copies of the Software, and to permit persons to whom the Software is 12 | * furnished to do so, subject to the following conditions: 13 | * 14 | * The above copyright notice and this permission notice shall be included in all 15 | * copies or substantial portions of the Software. 16 | * 17 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 18 | * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 19 | * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 20 | * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 21 | * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 22 | * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 23 | * SOFTWARE. 24 | * 25 | * Author: Randoms 26 | *******************************************************************************/ 27 | 28 | #ifndef __UDP_NODE_H_ 29 | #define __UDP_NODE_H_ 30 | 31 | #include 32 | #include 33 | #include 34 | #include 35 | #endif -------------------------------------------------------------------------------- /src/udp_publisher.cpp: -------------------------------------------------------------------------------- 1 | /****************************************************************************** 2 | * 3 | * The MIT License (MIT) 4 | * 5 | * Copyright (c) 2018 Bluewhale Robot 6 | * 7 | * Permission is hereby granted, free of charge, to any person obtaining a copy 8 | * of this software and associated documentation files (the "Software"), to deal 9 | * in the Software without restriction, including without limitation the rights 10 | * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 11 | * copies of the Software, and to permit persons to whom the Software is 12 | * furnished to do so, subject to the following conditions: 13 | * 14 | * The above copyright notice and this permission notice shall be included in all 15 | * copies or substantial portions of the Software. 16 | * 17 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 18 | * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 19 | * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 20 | * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 21 | * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 22 | * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 23 | * SOFTWARE. 24 | * 25 | * Author: Randoms 26 | *******************************************************************************/ 27 | 28 | #include "udp_node.h" 29 | #include 30 | 31 | int main(int argc, char **argv) 32 | { 33 | ros::init(argc, argv, "udp_pub_node"); 34 | ros::AsyncSpinner spinner(4); 35 | spinner.start(); 36 | ros::NodeHandle private_nh("~"); 37 | ros::Publisher test_pub = private_nh.advertise("/chatter", 10); 38 | while (ros::ok()) 39 | { 40 | std_msgs::String data; 41 | data.data = "hello"; 42 | test_pub.publish(data); 43 | ROS_INFO_STREAM("publish: hello"); 44 | sleep(1); 45 | } 46 | } -------------------------------------------------------------------------------- /src/udp_node.cpp: -------------------------------------------------------------------------------- 1 | /****************************************************************************** 2 | * 3 | * The MIT License (MIT) 4 | * 5 | * Copyright (c) 2018 Bluewhale Robot 6 | * 7 | * Permission is hereby granted, free of charge, to any person obtaining a copy 8 | * of this software and associated documentation files (the "Software"), to deal 9 | * in the Software without restriction, including without limitation the rights 10 | * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 11 | * copies of the Software, and to permit persons to whom the Software is 12 | * furnished to do so, subject to the following conditions: 13 | * 14 | * The above copyright notice and this permission notice shall be included in all 15 | * copies or substantial portions of the Software. 16 | * 17 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 18 | * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 19 | * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 20 | * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 21 | * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 22 | * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 23 | * SOFTWARE. 24 | * 25 | * Author: Randoms 26 | *******************************************************************************/ 27 | 28 | #include "udp_node.h" 29 | 30 | void print_message(const std_msgs::String data) 31 | { 32 | ROS_INFO_STREAM("received: " << data); 33 | } 34 | 35 | int main(int argc, char **argv) 36 | { 37 | ros::init(argc, argv, "udp_test_node"); 38 | ros::AsyncSpinner spinner(4); 39 | spinner.start(); 40 | ros::NodeHandle private_nh("~"); 41 | ros::Subscriber chatter_sub = private_nh.subscribe("/chatter", 10, print_message, 42 | ros::TransportHints().unreliable().maxDatagramSize(1000)); 43 | while (ros::ok()) 44 | { 45 | sleep(1); 46 | } 47 | } --------------------------------------------------------------------------------