add python2 demo

This commit is contained in:
Robot 2022-01-04 18:08:11 +08:00
parent adef5ea5ed
commit 003cb57186
19 changed files with 26944 additions and 0 deletions

View File

@ -0,0 +1,205 @@
cmake_minimum_required(VERSION 3.0.2)
project(wpb_home_python)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES wpb_home_python
# CATKIN_DEPENDS rospy std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/wpb_home_python.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/wpb_home_python_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_wpb_home_python.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,62 @@
<launch>
<master auto="start"/>
<!-- wpb_home core-->
<node pkg="wpb_home_bringup" type="wpb_home_core" name="wpb_home_core" output="screen">
<param name="serial_port" type="string" value="/dev/ftdi"/>
<rosparam file="$(find wpb_home_bringup)/config/wpb_home.yaml" command="load" />
</node>
<!--- Run Rplidar -->
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/rplidar"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<remap from="scan" to="scan_raw"/>
</node>
<!-- Run lidar filter -->
<node pkg="wpb_home_bringup" type="wpb_home_lidar_filter" name="wpb_home_lidar_filter">
<param name="pub_topic" value="/scan"/>
</node>
<!-- Run the map server -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find wpb_home_tutorials)/maps/map.yaml"/>
<!--- Run AMCL -->
<include file="$(find wpb_home_tutorials)/nav_lidar/amcl_omni.launch" />
<!--- Run move base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find wpb_home_tutorials)/nav_lidar/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find wpb_home_tutorials)/nav_lidar/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find wpb_home_tutorials)/nav_lidar/local_costmap_params.yaml" command="load" />
<rosparam file="$(find wpb_home_tutorials)/nav_lidar/global_costmap_params.yaml" command="load" />
<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="use_dijkstra" value="true"/>
<param name="base_local_planner" value="wpbh_local_planner/WpbhLocalPlanner" />
<param name= "controller_frequency" value="10" type="double"/>
</node>
<!-- RViz and TF tree -->
<arg name="model" default="$(find wpb_home_bringup)/urdf/wpb_home_mani.urdf"/>
<arg name="gui" default="true" />
<arg name="rvizconfig" default="$(find waterplus_map_tools)/rviz/nav.rviz" />
<param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
<!-- Map tools -->
<node pkg="waterplus_map_tools" type="wp_manager" name="wp_manager" output="screen"/>
<!-- WP_navi_server -->
<node pkg="waterplus_map_tools" type="wp_navi_server" name="wp_navi_server" output="screen"/>
</launch>

View File

@ -0,0 +1,65 @@
<?xml version="1.0"?>
<package format="2">
<name>wpb_home_python</name>
<version>0.0.0</version>
<description>The wpb_home_python package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="robot@todo.todo">robot</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/wpb_home_python</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@ -0,0 +1,57 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from wpb_home_behaviors.msg import Coord
from std_msgs.msg import String
from geometry_msgs.msg import Pose
# 标记变量,是否处于抓取过程当中
grabbing = False
# 物品检测回调函数
def cbObject(msg):
global grabbing
if grabbing == False:
num = len(msg.name)
rospy.loginfo("检测物品个数 = %d", num)
if num > 0:
rospy.logwarn("抓取目标 %s! (%.2f , %.2f , %.2f)",msg.name[0],msg.x[0],msg.y[0],msg.z[0]);
grab_msg = Pose()
grab_msg.position.x = msg.x[0]
grab_msg.position.y = msg.y[0]
grab_msg.position.z = msg.z[0]
global grab_pub
grab_pub.publish(grab_msg)
grabbing = True
# 已经获取物品坐标,停止检测
behavior_msg = String()
behavior_msg.data = "object_detect stop"
behaviors_pub.publish(behavior_msg)
# 抓取执行结果回调函数
def cbGrabResult(msg):
rospy.logwarn("抓取执行结果 = %s",msg.data)
# 主函数
if __name__ == "__main__":
rospy.init_node("grab_node")
# 发布物品检测激活话题
behaviors_pub = rospy.Publisher("/wpb_home/behaviors", String, queue_size=10)
# 发布抓取行为激活话题
grab_pub = rospy.Publisher("/wpb_home/grab_action", Pose, queue_size=10)
# 订阅物品检测结果的话题
object_sub = rospy.Subscriber("/wpb_home/objects_3d", Coord, cbObject, queue_size=10)
# 订阅抓取执行结果的话题
result_sub = rospy.Subscriber("/wpb_home/grab_result", String, cbGrabResult, queue_size=10)
# 延时三秒,让后台的话题初始化操作能够完成
d = rospy.Duration(3.0)
rospy.sleep(d)
# 发送消息,激活物品检测行为
msg = String()
msg.data = "object_detect start"
behaviors_pub.publish(msg)
rospy.spin()

View File

@ -0,0 +1,30 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
capture_one_frame = True
# 彩色图像回调函数
def cbImage(msg):
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
# 弹出窗口显示图片
cv2.imshow("Image window", cv_image)
cv2.waitKey(1)
# 保存图像到文件
global capture_one_frame
if capture_one_frame == True:
cv2.imwrite('/home/robot/1.jpg', cv_image)
rospy.logwarn("保存图片成功!")
capture_one_frame = False
# 主函数
if __name__ == "__main__":
rospy.init_node("image_data")
# 订阅机器人视觉传感器Kinect2的图像话题
image_sub = rospy.Subscriber("/kinect2/hd/image_color_rect",Image,cbImage,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,31 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
# 彩色图像回调函数
def cbImage(msg):
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
#转换为灰度图
gray_img=cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
#创建一个级联分类器
face_casecade = cv2.CascadeClassifier('/home/robot/catkin_ws/src/wpb_home_python/config/haarcascade_frontalface_alt.xml')
#人脸检测
face = face_casecade.detectMultiScale(gray_img, 1.3, 5)
for (x,y,w,h) in face:
#在原图上绘制矩形
cv2.rectangle(cv_image,(x,y),(x+w,y+h),(0,0,255),3)
# 弹出窗口显示图片
cv2.imshow("face window", cv_image)
cv2.waitKey(1)
# 主函数
if __name__ == "__main__":
rospy.init_node("image_face_detect")
# 订阅机器人视觉传感器Kinect2的图像话题
image_sub = rospy.Subscriber("/kinect2/hd/image_color_rect",Image,cbImage,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,35 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sensor_msgs.msg import LaserScan
from geometry_msgs.msg import Twist
count = 0
# 激光雷达回调函数
def cbScan(msg):
global vel_pub
global count
vel_msg = Twist()
dist = msg.ranges[180]
rospy.logwarn("正前方测距数值 = %.2f",dist)
if count > 0:
count = count -1
rospy.loginfo("持续转向 count = %d",count)
return
if dist > 1.5:
vel_msg.linear.x = 0.05
else:
vel_msg.angular.z = 0.3
count = 50
vel_pub.publish(vel_msg)
# 主函数
if __name__ == "__main__":
rospy.init_node("lidar_behavior")
# 发布机器人运动控制话题
vel_pub = rospy.Publisher("cmd_vel",Twist,queue_size=10)
# 订阅激光雷达的数据话题
lidar_sub = rospy.Subscriber("scan",LaserScan,cbScan,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,17 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sensor_msgs.msg import LaserScan
# 激光雷达回调函数
def cbScan(msg):
rospy.loginfo("雷达数据个数 = %d",len(msg.ranges))
rospy.logwarn("正前方测距数值 = %.2f",msg.ranges[180])
# 主函数
if __name__ == "__main__":
rospy.init_node("lidar_data")
# 订阅激光雷达的数据话题
lidar_sub = rospy.Subscriber("scan",LaserScan,cbScan,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,53 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sensor_msgs.msg import JointState
state = 0
if __name__ == "__main__":
rospy.init_node("mani_ctrl")
# 发布机械臂控制话题
mani_pub = rospy.Publisher("/wpb_home/mani_ctrl",JointState,queue_size=30)
# 构造机械臂控制消息并进行赋值
msg = JointState()
msg.name = ['lift', 'gripper']
msg.position = [ 0 , 0 ]
msg.velocity = [ 0 , 0 ]
rospy.loginfo("bef")
# 延时三秒,让后台的话题发布操作能够完成
d = rospy.Duration(3.0)
rospy.sleep(d)
# 构建发送频率对象
rate = rospy.Rate(0.1)
while not rospy.is_shutdown():
if state == 0:
rospy.loginfo("[mani_ctrl] ZERO -> DOWN")
msg.position[0] = 0.5 # 升降高度(单位:米)
msg.velocity[0] = 0.5 #升降速度(单位:米/秒)
msg.position[1] = 0.1 #手爪指间距(单位:米)
msg.velocity[1] = 5 #手爪开合角速度(单位:度/秒)
if state == 1:
rospy.loginfo("[mani_ctrl] DOWN -> UP")
msg.position[0] = 1.0 # 升降高度(单位:米)
msg.velocity[0] = 0.5 #升降速度(单位:米/秒)
msg.position[1] = 0 #手爪指间距(单位:米)
msg.velocity[1] = 5 #手爪开合角速度(单位:度/秒)
if state == 2:
rospy.loginfo("[mani_ctrl] UP -> DOWN")
msg.position[0] = 0.5 # 升降高度(单位:米)
msg.velocity[0] = 0.5 #升降速度(单位:米/秒)
msg.position[1] = 0.1 #手爪指间距(单位:米)
msg.velocity[1] = 5 #手爪开合角速度(单位:度/秒)
if state == 3:
rospy.loginfo("[mani_ctrl] DOWN -> ZERO")
msg.position[0] = 0 # 升降高度(单位:米)
msg.velocity[0] = 0.5 #升降速度(单位:米/秒)
msg.position[1] = 0.1 #手爪指间距(单位:米)
msg.velocity[1] = 5 #手爪开合角速度(单位:度/秒)
mani_pub.publish(msg)
rate.sleep()
state += 1
if state == 4:
state = 0

View File

@ -0,0 +1,27 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from std_msgs.msg import String
# 导航结果回调函数
def resultNavi(msg):
rospy.loginfo("导航结果 = %s",msg.data)
if __name__ == "__main__":
rospy.init_node("map_tools_navi")
# 发布航点名称话题
waypoint_pub = rospy.Publisher("/waterplus/navi_waypoint",String,queue_size=10)
# 订阅导航结果话题
result_sub = rospy.Subscriber("/waterplus/navi_result",String,resultNavi,queue_size=10)
# 延时1秒钟让后台的话题发布操作能够完成
rospy.sleep(1)
# 构建航点名称消息包
msg = String()
msg.data = '1'
# 发送航点名称消息包
waypoint_pub.publish(msg)
# 构建循环让程序别退出,等待导航结果
rate = rospy.Rate(10)
while not rospy.is_shutdown():
rate.sleep()

View File

@ -0,0 +1,33 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from wpb_home_behaviors.msg import Coord
from std_msgs.msg import String
# 物品检测回调函数
def cbObject(msg):
print("------------------------------------------")
rospy.loginfo("检测物品个数 = %d",len(msg.name))
for i in range(len(msg.name)):
rospy.logwarn("%d号物品 %s 坐标为(%.2f, %.2f, %.2f) ",
i, msg.name[i], msg.x[i], msg.y[i], msg.z[i] )
# 主函数
if __name__ == "__main__":
rospy.init_node("object_detect")
# 发布物品检测激活话题
behaviors_pub = rospy.Publisher("/wpb_home/behaviors", String, queue_size=10)
# 订阅物品检测结果的话题
object_sub = rospy.Subscriber("/wpb_home/objects_3d", Coord, cbObject, queue_size=10)
# 延时三秒,让后台的话题初始化操作能够完成
d = rospy.Duration(3.0)
rospy.sleep(d)
# 发送消息,激活物品检测行为
msg = String()
msg.data = "object_detect start"
behaviors_pub.publish(msg)
rospy.spin()

View File

@ -0,0 +1,22 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sensor_msgs.msg import PointCloud2
import sensor_msgs.point_cloud2 as pc2
# 三维点云回调函数
def callbackPointcloud(msg):
# 从点云中提取三维坐标数值
pc = pc2.read_points(msg, skip_nans=True, field_names=("x", "y", "z"))
point_cnt = 0
for p in pc:
rospy.loginfo("%d点坐标 (x= %.2f, y= %.2f, z= %.2f)",point_cnt, p[0],p[1],p[2] )
point_cnt += 1
# 主函数
if __name__ == "__main__":
rospy.init_node("pointcloud_data")
# 订阅机器人视觉传感器Kinect2的三维点云话题
pc_sub = rospy.Subscriber("/kinect2/sd/points",PointCloud2, callbackPointcloud,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,25 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sensor_msgs.msg import PointCloud2
import sensor_msgs.point_cloud2 as pc2
# 三维点云回调函数
def callbackPointcloud(msg):
field_num = len(msg.fields)
rospy.logwarn("PointField元素个数 = %d",field_num)
print("--------------------------------")
for f in msg.fields:
rospy.loginfo("name = %s", f.name)
rospy.loginfo("offset = %d", f.offset)
rospy.loginfo("datatype = %d", f.datatype)
rospy.loginfo("count = %d", f.count)
print("--------------------------------")
# 主函数
if __name__ == "__main__":
rospy.init_node("pointcloud_field")
# 订阅机器人视觉传感器Kinect2的三维点云话题
pc_sub = rospy.Subscriber("/kinect2/sd/points",PointCloud2, callbackPointcloud,queue_size=10)
rospy.spin()

View File

@ -0,0 +1,33 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
import actionlib
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
if __name__ == "__main__":
rospy.init_node("simple_goal")
# 生成一个导航请求客户端
ac = actionlib.SimpleActionClient('move_base',MoveBaseAction)
# 等待服务器端启动
ac.wait_for_server()
# 构建目标航点消息
goal = MoveBaseGoal()
# 目标航点的参考坐标系
goal.target_pose.header.frame_id="map"
# 目标航点在参考坐标系里的三维数值
goal.target_pose.pose.position.x = 1.0
goal.target_pose.pose.position.y = 0.0
goal.target_pose.pose.position.z = 0.0
# 目标航点在参考坐标系里的朝向信息
goal.target_pose.pose.orientation.x = 0.0
goal.target_pose.pose.orientation.y = 0.0
goal.target_pose.pose.orientation.z = 0.0
goal.target_pose.pose.orientation.w = 1.0
# 发送目标航点去执行
ac.send_goal(goal)
rospy.loginfo("开始导航……")
ac.wait_for_result()
rospy.loginfo("导航结束!")

View File

@ -0,0 +1,22 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from sound_play.msg import SoundRequest
# 主函数
if __name__ == "__main__":
rospy.init_node("speak_node")
# 发布语音内容话题
speak_pub = rospy.Publisher("/robotsound", SoundRequest, queue_size=20)
rate = rospy.Rate(0.2)
while not rospy.is_shutdown():
# 发送消息,让语音节点发声
msg = SoundRequest()
msg.sound = SoundRequest.SAY
msg.command = SoundRequest.PLAY_ONCE
msg.volume = 1.0
msg.arg = "hello world"
speak_pub.publish(msg)
rate.sleep()

View File

@ -0,0 +1,23 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from std_msgs.msg import String
# 语音识别回调函数
def cbKeyword(msg):
rospy.logwarn("语音识别结果 = %s", msg.data)
if msg.data == "你叫什么名字":
spk_msg = String()
spk_msg.data = "我是路西,你呢?"
spk_pub.publish(spk_msg)
# 主函数
if __name__ == "__main__":
rospy.init_node("sr_cn_node")
# 订阅语音识别结果的话题
sr_sub = rospy.Subscriber("/xfyun/iat", String, cbKeyword, queue_size=10)
# 发布语音说话内容的话题
spk_pub = rospy.Publisher("/xfyun/tts", String, queue_size=10)
rospy.spin()

View File

@ -0,0 +1,23 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from std_msgs.msg import String
# 语音识别回调函数
def cbKeyword(msg):
rospy.logwarn("语音识别结果 = %s", msg.data)
if msg.data == "Hello":
spk_msg = String()
spk_msg.data = "Hi"
spk_pub.publish(spk_msg)
# 主函数
if __name__ == "__main__":
rospy.init_node("sr_en_node")
# 订阅语音识别结果的话题
sr_sub = rospy.Subscriber("/xfyun/iat", String, cbKeyword, queue_size=10)
# 发布语音说话内容的话题
spk_pub = rospy.Publisher("/xfyun/tts", String, queue_size=10)
rospy.spin()

View File

@ -0,0 +1,20 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from geometry_msgs.msg import Twist
if __name__ == "__main__":
rospy.init_node("velocity_command")
# 发布速度控制话题
vel_pub = rospy.Publisher("cmd_vel",Twist,queue_size=10)
# 构建速度消息包并赋值
msg = Twist()
msg.linear.x = 0.1
# msg.angular.z =0.1
# 构建发送频率对象
rate = rospy.Rate(10)
while not rospy.is_shutdown():
rospy.loginfo("发送一个速度消息包")
vel_pub.publish(msg)
rate.sleep()