ROS学习-----通过python语言,进行自定义消息的通信话题编程目录
一、创建自定义消息文件[.msg]
1、进入项目工程包、创建msg文件
2、打开个人信息文件,录入我们个人信息的属性
二、配置package.xml文件内容
1、进入项目包目录下,打开package.xml
2、将package.xml文件中加入如下配置
三、配置CMakeLists文件
1、进入项目包目录下,打开CMakeLists.txt文件
2、将文件内容作如下替换
3、回到ROS工作空间,进行编译
四、编写我们python的发送和接收信息文件
1、在项目工程包下创建python文件夹,用于存放我们的python文件
2、编写python发送信息代码文件[Person_Publisher.py]
3、编写python接收信息代码文件[Person_Subscriber.py]
五、通过ROS节点、运行我们的发送接收的python文件
1、在当前终端启动ROS
2、再新建一个终端,运行我们接收信息文件Person_Subscriber.py
3、新建一个终端,运行我们发送信息文件Person_Publisher.py文件

在进行ROS嵌入式的学习时,我们可以发现用C/C++进行ROS编程有一定的局限性,例如:
语言过于复杂
代码繁琐
理解起来较难
语言限制规则多等
这时候,我们想到的是将python编程与ROS相结合,进行二次创作,python代码的简洁性结合ROS的嵌入式学习,能够让同学学习得更加透彻,因此、本次博客,林君学长主要带大家了解,如何在ROS环境下,通过python编程进行自定义的消息通信
以在ROS中发送和接收个人信息为例
一、创建自定义消息文件[.msg]
1、进入项目工程包、创建msg文件
1)、进入自己ROS工作环境下的项目工程包comm

cd ros/src/comm/

注意:上面的comm是林君自己的工程包哦,大家根据自己的进行修改
2)、在该项目工程包下面创建我们msg文件夹

mkdir msg
13)、进入msg消息文件夹,创建我们的个人消息文件Person.msg

cd msg
touch Person.msg

2、打开个人信息文件,录入我们个人信息的属性
1)、打开个人信息文件,录入我们个人信息的属性

打开Person.msg文件
gedit Person.msg
1将如下个人基本信息属性填入文件内容:

string name
uint8 sex
uint8 age

uint8 woman =0
uint8 man =1
uint8 manplus =2

上面代码中,姓名、年龄、年龄不用解释、这里性别用整形代替、0代表女性、1代表男性、2代表成年男性

  • 如下所示,填写好之后,点击保存,然后关闭
    在这里插入图片描述

二、配置package.xml文件内容
1、进入项目包目录下,打开package.xml
1)、进入项目包

cd ~/ros/src/comm/

2)、打开package.xml文件

gedit package.xml

2、将package.xml文件中加入如下配置
1)、找到文件中的 <build_depend> 加入如下设置:

<build_depend>message_generation</build_depend>

2)、找到文件中的 <exec_depend> 加入如下设置:

<exec_depend>message_runtime</exec_depend>

三、配置CMakeLists文件
1、进入项目包目录下,打开CMakeLists.txt文件
1)、进入项目包

cd ~/ros/src/comm/

2)、打开CMakeLists.txt文件

gedit CMakeLists.txt

2、将文件内容作如下替换
1)、找到find_package函数,在里面加入如下代码:

message_generation

如下所示:

在这里插入图片描述

、找到add_message_files函数,在里面添加如下命令:

Person.msg

如下所示:
在这里插入图片描述

找到catkin_package函数,在函数里面添加如下代码:

essage_runtime

如下所示:
在这里插入图片描述
到这里,我们配置文件就设置好了,可以进行编译了!

3、回到ROS工作空间,进行编译

1)、回到ROS工作空间

cd ~/ros

2)、编译文件

catkin_make

成功编译的结果如下所示:

在这里插入图片描述

提示:编译中出现错误,可以根据提示进行修改哦!不要惊慌

四、编写我们python的发送和接收信息文件
1、在项目工程包下创建python文件夹,用于存放我们的python文件
1)、进入工程包

cd ~/ros/src/comm/

2)、创建python文件夹

mkdir python

3)、计入该python文件夹

cd python

2、编写python发送信息代码文件[Person_Publisher.py]
1)、创建Person_Publisher.py文件

touch Person_Publisher.py

2)、打开Person_Publisher.py文件

gedit Person_Publisher.py

3)、将以下发送信息代码写入文件内容

#!/usr/bin/env python
#coding: utf-8
#  comm/Person   personmsg
import rospy
from comm.msg import Person
def Person_Publisher():
    rospy.init_node('Person_publisher', anonymous = True)
    pub = rospy.Publisher('Personmsg',Person, queue_size = 10)
    rate = rospy.Rate(5)
    while not rospy.is_shutdown():
        msg = Person()
        msg.name = "lenovoLin";
        msg.age = 22;
        msg.sex = Person.man;
        pub.publish(msg)
        rospy.loginfo("this publish person message;[ %s, %d, %d]",
                      msg.name, msg.age ,msg.sex)
        rate.sleep()
if __name__ == '__main__':
    try:
        Person_Publisher()
    except rospy.ROSInterruptException:
        pass

、点击保存,关闭文件
在这里插入图片描述
5)、为Person_Publisher.py添加执行权限

chmod 777 Person_Publisher.py

3、编写python接收信息代码文件[Person_Subscriber.py]
1)、创建Person_Subscriber.py文件

touch Person_Subscriber.py

2)、打开Person_Subscriber.py文件

gedit Person_Subscriber.py

3)、将以下接收信息代码写入文件内容

#!/usr/bin/env python
# coding: utf-8
# 本代码是以Person_Publisher话题,消息类型为comm::Person
import rospy
from comm.msg import Person
def PublishInfoCallback(msg):
    rospy.loginfo("this is Person Publisher messgae:[name:%s, age:%d, sex:%d]",msg.name, msg.age, msg.sex)
def Person_Subscriber():
    # ROS节点初始化
    rospy.init_node('Person_Subscriber', anonymous=True)
    # 创建一个Subscriber,订阅名为Personmsg的topic,注册回调函数personInfoCallback
    rospy.Subscriber("Personmsg", Person, PublishInfoCallback)
    # 循环等待回调函数
    rospy.spin()
if __name__ == '__main__':
    Person_Subscriber()

点击保存,关闭文件
在这里插入图片描述
5)、为Person_Subscriber.py添加执行权限

chmod 777 Person_Subscriber.py

五、通过ROS节点、运行我们的发送接收的python文件
1、在当前终端启动ROS
1)、进入ROS工作空间

cd ~/ros

2)、启动ROS

roscore


2、再新建一个终端,运行我们接收信息文件Person_Subscriber.py
1)、进入工作空间

cd ~/ros

2)、注册程序

source ./devel/setup.bash

3)、通过节点运行Person_Subscriber.py文件

rosrun comm Person_Subscriber.py

在这里插入图片描述
目前在等待接收信息状态

3、新建一个终端,运行我们发送信息文件Person_Publisher.py文件
1)、进入工作空间

cd ~/ros

2)、注册程序

source ./devel/setup.bash

3)、通过节点运行Person_Publisher.py文件

rosrun comm Person_Publisher.py

4)、回车进行运行,查看两个终端的状态如下所示:

有上面可以看出,
发送程序发送个人信息如下:
姓名:LenovoLin
年龄:22
性别:1---->男
接收程序接收信息如下:
姓名:LenovoLin
年龄:22
性别:1---->男
发送和接收一致,实验完美成功,这个例题,我们完成得很不错!
以上就是本次博客的全部内容啦,希望对于本次博客的阅读,可以帮你大家更好的理解如何在ROS下进行python的通信编程,这是以后学习ROS嵌入式很重要的一种手段哦,现在知道python的重要性了吧!
遇到问题的小伙伴、请在评论区进行留言哦,林君学长看到了会给大家解答的!这个学长不太冷!
陈一月的又一天编程岁月^ _ ^