古月居 ROS入门21讲 第十讲 发布者Publisher的编程实现

古月居 ROS入门21讲 第十讲 发布者Publisher的编程实现

  • C++
    velocity_publisher.cpp
#include<ros/ros.h>
#include<geometry_msgs/Twist.h>

int main(int argc,char**argv)
{
    ros::init(argc,argv,"velocity_publisher");
    ros::NodeHandle n;
    ros::Publisher turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel",10);
    ros::Rate loop_rate(10);
    while(ros::ok())
    {
        geometry_msgs::Twist vel_msgs;
	vel_msgs.linear.x=0.5;
        vel_msgs.angular.z=0.2;
        
        turtle_vel_pub.publish(vel_msgs);
        ROS_INFO("Publish turtle velocity command[%0.2f m/s,%0.2f rad/s]",vel_msgs.linear.x,vel_msgs.angular.z);
        loop_rate.sleep();	
    }
    return 0;
}

在CMakelists.txt中添加

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

编译

cd ~/catkin_ws/
source devel/setup.bash #或直接在.bashrc中添加source ~/catkin_ws/devel/setup.bash
catkin_make

运行

roscore
rosrun turtlesim turtlesim_node
rosrun learning_topic pose_subscriber
  • Python
    velocity_publisher.py
#!/usr/bin/env python 
# -*- coding:utf-8 -*-
import rospy
from geometry_msgs.msg import Twist

def velocity_publisher():
    rospy.init_node('velocity_publisher',anonymous=True)
    turtle_vel_pub=rospy.Publisher('/turtle1/cmd_vel',Twist,queue_size=10)
    rate=rospy.Rate(10)
    while not rospy.is_shutdown():
        vel_msg=Twist()
        vel_msg.angular.z=0.2
        vel_msg.linear.x=0.5

        turtle_vel_pub.publish(vel_msg)
        rospy.loginfo("Publish 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

#!/usr/bin/env python作用:是指定Python解释器,在环境变量中寻找,也可以直接指定Python解释器的路径,通过命令which python来查看python解释器的位置
# -*- coding:utf-8 -*-作用:指定编码为utf-8,不加的话代码中若有中文注释可能报错
Python文件不需要编译,但是需要添加执行权限,使用命令sudo chmod +x velocity_publisher.py或:
在这里插入图片描述
运行

roscore
rosrun turtlesim turtlesim_node
rosrun learning_topic pose_subscriber.py
评论 3
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值