ROS(五)——发布者Publisher的编程实现(C++ & Python)

通过程序控制让海龟仿真器中的海龟动起来

 

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第1张图片

turtle velocity速度值的发布者

发布一个message

message的一个数据结构是我们之前看到的Twist的消息, 会分成线速度、角速度

通过Topic将数据传送给Subscriber,Subscriber通过订阅得到数据,控制海龟发生运动

 

 

创建功能包

catkin_create_pkg learning_topic roscpp rospy std_msgs geometry_msgs turtlesim

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第2张图片

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第3张图片

 

创建发布者代码(C++)

如何实现一个发布者

  • 初始化ROS节点;
  • 向ROS Master注册节点信息,包括发布的话题名和话题中的消息类型;
  • 创建消息数据;
  • 按照一定频率循环发布消息。

 

velocity_publisher.cpp

/**
 * 该例程将发布turtle1/cmd_vel话题,消息类型geometry_msgs::Twist
 */
 
#include 
#include 

int main(int argc, char **argv)
{
	// ROS节点初始化
	ros::init(argc, argv, "velocity_publisher");

	// 创建节点句柄
	ros::NodeHandle n;

	// 创建一个Publisher,发布名为/turtle1/cmd_vel的topic,消息类型为geometry_msgs::Twist,队列长度10
	ros::Publisher turtle_vel_pub = n.advertise("/turtle1/cmd_vel", 10);

	// 设置循环的频率
	ros::Rate loop_rate(10);

	int count = 0;
	while (ros::ok())
	{
	    // 初始化geometry_msgs::Twist类型的消息
		geometry_msgs::Twist vel_msg;
		vel_msg.linear.x = 0.5;
		vel_msg.angular.z = 0.2;

	    // 发布消息
		turtle_vel_pub.publish(vel_msg);
		ROS_INFO("Publsh turtle velocity command[%0.2f m/s, %0.2f rad/s]", 
				vel_msg.linear.x, vel_msg.angular.z);

	    // 按照循环频率延时
	    loop_rate.sleep();
	}

	return 0;
}

将velocity_publisher.cpp放到learning_topic的src目录下

 

配置发布者代码编译规则

 

如何配置CMakeLists.txt中的编译规则

  • 设置需要编译的代码和生成的可执行文件
  • 设置链接库

 

修改learning_topic中的CMakeLists.txt

add_executable(velocity_publisher src/velocity_publisher.cpp)
target_link_libraries(velocity_publisher ${catkin_LIBRARIES})

add_executable用来描述要把哪一个程序文件编译成哪一个可执行文件的, 即要把src/velocity_publisher.cpp编译成velocity_publisher可执行文件

 

放在build部分的末尾

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第4张图片

 

编译并运行发布者

回到编译空间的根目录 catkin_ws

catkin_make

这里有代码了,编译就要等一会了

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第5张图片

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第6张图片

 

设置环境变量

source devel/setup.bash

运行

roscore
rosrun turtlesim turtlesim_node
rosrun learningtopic velocity_publisher

注意这里运行的是velocity_publisher,不是velocity_publisher.cpp,是经过编译后的

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第7张图片

ctrl+c就可以停止

 

 

python代码的程序

为了避免混了,新建一个scripts目录放置python文件

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第8张图片

 

在ROS中运行python文件一定要注意要让python文件具有可执行权限

右键文件,属性,这里打上对勾

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第9张图片

 

velocity_publisher.py

#!/usr/bin/python
# -*- coding: utf-8 -*-
# 该例程将发布turtle1/cmd_vel话题,消息类型geometry_msgs::Twist

import rospy
from geometry_msgs.msg import Twist

def velocity_publisher():
	# ROS节点初始化
    rospy.init_node('velocity_publisher', anonymous=True)

	# 创建一个Publisher,发布名为/turtle1/cmd_vel的topic,消息类型为geometry_msgs::Twist,队列长度10
    turtle_vel_pub = rospy.Publisher('/turtle1/cmd_vel', Twist, queue_size=10)

	#设置循环的频率
    rate = rospy.Rate(10) 

    while not rospy.is_shutdown():
		# 初始化geometry_msgs::Twist类型的消息
        vel_msg = Twist()
        vel_msg.linear.x = 0.5
        vel_msg.angular.z = 0.2

		# 发布消息
        turtle_vel_pub.publish(vel_msg)
    	rospy.loginfo("Publsh turtle velocity command[%0.2f m/s, %0.2f rad/s]", 
				vel_msg.linear.x, vel_msg.angular.z)

		# 按照循环频率延时
        rate.sleep()

if __name__ == '__main__':
    try:
        velocity_publisher()
    except rospy.ROSInterruptException:
        pass


代码流程什么的都和C++一样

 

 

python文件是不用重新去编译的,可以直接运行

就是将python文件放在scripts目录下之后,就开始下面执行就行了

注意要设置环境变量

这里输入到rosrun learning_to 按几次tab键,就可以出现可以运行的几个程序

注意这里运行的是velocity_publisher.py ,不是velocity_publisher,那是cpp程序编译后的

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第10张图片

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第11张图片

ROS(五)——发布者Publisher的编程实现(C++ & Python)_第12张图片

默认用的是python2

 

你可能感兴趣的:(ROS)