ROS2贪吃龟练习工程

2024-05-30 13:20
文章标签 练习 工程 ros2 贪吃

本文主要是介绍ROS2贪吃龟练习工程,希望对大家解决编程问题提供一定的参考价值,需要的开发者们随着小编来一起学习吧!

本文是ROS2基础知识的综合小应用,练习如何创建工作包,创建Node,定义Topic和Service,以及通过LaunchFile启动多个节点。基础知识可以参考:ROS2基础编程,ROS2 Topics和Services,ROS2 LaunchFile和Parameter
更多内容,访问专栏目录获取实时更新。

创建工作包

ros2 pkg create turtlesim_greedy_turtle --build-type ament_python

创建节点

touch turtle_controller.py
touch turtle_spawner.py
chmod +x turtle_controller.py
chmod +x turtle_spawner.py

添加依赖

<depend>rclpy</depend>
<depend>turtlesim</depend>
<depend>geometry_msgs</depend>
<depend>my_robot_interfaces</depend>

创建Msg
Turtle.msg

string name
float64 x
float64 y
float64 theta

TurtleArray.msg

Turtle[] turtles

创建Srv
CatchTurtle.srv

string name
---
bool success

添加节点控制Turtle
turtle_controller.py

#!/usr/bin/env python3
import rclpy
import math
from functools import partial
from rclpy.node import Node
from turtlesim.msg import Pose
from geometry_msgs.msg import Twist
from my_robot_interfaces.msg import Turtle
from my_robot_interfaces.msg import TurtleArray
from my_robot_interfaces.srv import CatchTurtleclass TurtleControllerNode(Node):def __init__(self):super().__init__("turtle_controller")self.pose = Noneself.turtle_to_catch = Noneself.pose_subscriber = self.create_subscription(Pose, "turtle1/pose", self.callback_turtle_pose, 10)self.cmd_vel_publisher = self.create_publisher(Twist, "turtle1/cmd_vel", 10)self.alive_turtles_subscriber = self.create_subscription(TurtleArray, "alive_turtles", self.callback_alive_turtles, 10)self.control_loop_timer = self.create_timer(0.01, self.control_loop)def callback_turtle_pose(self, msg):self.pose = msgdef control_loop(self):if self.pose == None or self.turtle_to_catch == None:return# calcu the distance between current position and target positiondist_x = self.turtle_to_catch.x - self.pose.xdist_y = self.turtle_to_catch.y - self.pose.ydistance  = math.sqrt(dist_x * dist_x + dist_y * dist_y)# construct cmd_vel msg to control the turtlemsg = Twist()if distance <= 0.5:  # target reachedmsg.linear.x = 0.0   # stop the turtlemsg.angular.z = 0.0self.call_catch_turtle_server(self.turtle_to_catch.name)self.turtle_to_catch = Noneelse:                # move to the target positionmsg.linear.x = 2 * distance  # optimizegoal_theta = math.atan2(dist_y, dist_x)  # orientationdiff = goal_theta - self.pose.thetaif diff > math.pi:diff -= 2 * math.pielif diff < -math.pi:diff += 2 * math.pimsg.angular.z = 6 * diff  # optimizeself.cmd_vel_publisher.publish(msg)def callback_alive_turtles(self, msg):if len(msg.turtles) > 0:self.turtle_to_catch = msg.turtles[0]def call_catch_turtle_server(self, turtle_name):client = self.create_client(CatchTurtle, "catch_turtle")while not client.wait_for_service(1.0):self.get_logger().warn("Waiting for server...")request = CatchTurtle.Request()request.name = turtle_namefuture = client.call_async(request)future.add_done_callback(partial(self.callback_call_catch_turtle, turtle_name=turtle_name))def callback_call_catch_turtle(self, future, turtle_name):try:response = future.result()if not response.success:self.get_logger().error("Turtle " + str(turtle_name) + " could not be caught")except Exception as e:self.get_logger().error("Service call failed %r" & (e,))def main(args=None):rclpy.init(args=args)node = TurtleControllerNode()rclpy.spin(node)rclpy.shutdown()if __name__ == "__main__":main()

添加节点产生或移除Turtle

#!/usr/bin/env python3
import rclpy
import random
import math
from functools import partial
from rclpy.node import Node
from turtlesim.srv import Spawn
from turtlesim.srv import Kill
from my_robot_interfaces.msg import Turtle
from my_robot_interfaces.msg import TurtleArray
from my_robot_interfaces.srv import CatchTurtleclass TurtleSpawnerNode(Node):def __init__(self):super().__init__("turtle_spawner")self.declare_parameter("spawn_frequency", 1.0)self.declare_parameter("turtle_name_prefix", "turtle")self.spawn_frequency = self.get_parameter("spawn_frequency").valueself.turtle_name_prefix = self.get_parameter("turtle_name_prefix").valueself.turtle_counter = 0self.alive_turtles = []self.spawn_turtle_timer = self.create_timer(1.0 / self.spawn_frequency, self.spawn_new_turtle)self.alive_turtles_publisher = self.create_publisher(TurtleArray, "alive_turtles", 10)self.catch_turtle_service = self.create_service(CatchTurtle, "catch_turtle", self.callback_catch_turtle)def spawn_new_turtle(self):self.turtle_counter += 1name = self.turtle_name_prefix + "_" + str(self.turtle_counter)x = random.uniform(0.0, 10.0)y = random.uniform(0.0, 10.0)theta = random.uniform(0.0, 2 * math.pi)self.call_spawn_server(name, x, y, theta)def call_spawn_server(self, turtle_name, x, y, theta):client = self.create_client(Spawn, "spawn")while not client.wait_for_service(1.0):self.get_logger().warn("Waiting for server...")request = Spawn.Request()request.name = turtle_namerequest.x = xrequest.y = yrequest.theta = thetafuture = client.call_async(request)future.add_done_callback(partial(self.callback_call_spawn, turtle_name=turtle_name, x=x, y=y, theta=theta))def callback_call_spawn(self, future, turtle_name, x, y, theta):try:response = future.result()if response.name != "":self.get_logger().info("Turtle " + response.name + " is now alive")new_turtle = Turtle()new_turtle.name = turtle_namenew_turtle.x = xnew_turtle.y = ynew_turtle.theta = thetaself.alive_turtles.append(new_turtle)self.publish_alive_turtles()except Exception as e:self.get_logger().error("Service call failed %r" % (e,))def publish_alive_turtles(self):msg = TurtleArray()msg.turtles = self.alive_turtlesself.alive_turtles_publisher.publish(msg)def callback_catch_turtle(self, request, response):self.call_kill_server(request.name)response.success = Truereturn responsedef call_kill_server(self, turtle_name):client = self.create_client(Kill, "kill")while not client.wait_for_service(1.0):self.get_logger().warn("Waiting for server...")request = Kill.Request()request.name = turtle_namefuture = client.call_async(request)future.add_done_callback(partial(self.callback_call_kill, turtle_name=turtle_name))def callback_call_kill(self, future, turtle_name):try:future.result()for (i, turtle) in enumerate(self.alive_turtles):if turtle.name == turtle_name:del self.alive_turtles[i]self.publish_alive_turtles()breakexcept Exception as e:self.get_logger().error("Service call failed %r" & (e,))def main(args=None):rclpy.init(args=args)node = TurtleSpawnerNode()rclpy.spin(node)rclpy.shutdown()if __name__ == "__main__":main()

创建LaunchFile
在这里插入图片描述

不要忘记更新my_robot_bringup工作包的package.xml添加依赖

通过LaunchFile启动

ros2 launch my_robot_bringup turtlesim_greedy_turtle.launch.py

最终的效果:
在这里插入图片描述

如有错误,欢迎留言或来信指正:hbin6358@163.com

这篇关于ROS2贪吃龟练习工程的文章就介绍到这儿,希望我们推荐的文章对编程师们有所帮助!



http://www.chinasem.cn/article/1016264

相关文章

Ilya-AI分享的他在OpenAI学习到的15个提示工程技巧

Ilya(不是本人,claude AI)在社交媒体上分享了他在OpenAI学习到的15个Prompt撰写技巧。 以下是详细的内容: 提示精确化:在编写提示时,力求表达清晰准确。清楚地阐述任务需求和概念定义至关重要。例:不用"分析文本",而用"判断这段话的情感倾向:积极、消极还是中性"。 快速迭代:善于快速连续调整提示。熟练的提示工程师能够灵活地进行多轮优化。例:从"总结文章"到"用

基于UE5和ROS2的激光雷达+深度RGBD相机小车的仿真指南(五):Blender锥桶建模

前言 本系列教程旨在使用UE5配置一个具备激光雷达+深度摄像机的仿真小车,并使用通过跨平台的方式进行ROS2和UE5仿真的通讯,达到小车自主导航的目的。本教程默认有ROS2导航及其gazebo仿真相关方面基础,Nav2相关的学习教程可以参考本人的其他博客Nav2代价地图实现和原理–Nav2源码解读之CostMap2D(上)-CSDN博客往期教程: 第一期:基于UE5和ROS2的激光雷达+深度RG

RabbitMQ练习(AMQP 0-9-1 Overview)

1、What is AMQP 0-9-1 AMQP 0-9-1(高级消息队列协议)是一种网络协议,它允许遵从该协议的客户端(Publisher或者Consumer)应用程序与遵从该协议的消息中间件代理(Broker,如RabbitMQ)进行通信。 AMQP 0-9-1模型的核心概念包括消息发布者(producers/publisher)、消息(messages)、交换机(exchanges)、

【Rust练习】12.枚举

练习题来自:https://practice-zh.course.rs/compound-types/enum.html 1 // 修复错误enum Number {Zero,One,Two,}enum Number1 {Zero = 0,One,Two,}// C语言风格的枚举定义enum Number2 {Zero = 0.0,One = 1.0,Two = 2.0,}fn m

MySql 事务练习

事务(transaction) -- 事务 transaction-- 事务是一组操作的集合,是一个不可分割的工作单位,事务会将所有的操作作为一个整体一起向系统提交或撤销请求-- 事务的操作要么同时成功,要么同时失败-- MySql的事务默认是自动提交的,当执行一个DML语句,MySql会立即自动隐式提交事务-- 常见案例:银行转账-- 逻辑:A给B转账1000:1.查询

Jenkins构建Maven聚合工程,指定构建子模块

一、设置单独编译构建子模块 配置: 1、Root POM指向父pom.xml 2、Goals and options指定构建模块的参数: mvn -pl project1/project1-son -am clean package 单独构建project1-son项目以及它所依赖的其它项目。 说明: mvn clean package -pl 父级模块名/子模块名 -am参数

html css jquery选项卡 代码练习小项目

在学习 html 和 css jquery 结合使用的时候 做好是能尝试做一些简单的小功能,来提高自己的 逻辑能力,熟悉代码的编写语法 下面分享一段代码 使用html css jquery选项卡 代码练习 <div class="box"><dl class="tab"><dd class="active">手机</dd><dd>家电</dd><dd>服装</dd><dd>数码</dd><dd

014.Python爬虫系列_解析练习

我 的 个 人 主 页:👉👉 失心疯的个人主页 👈👈 入 门 教 程 推 荐 :👉👉 Python零基础入门教程合集 👈👈 虚 拟 环 境 搭 建 :👉👉 Python项目虚拟环境(超详细讲解) 👈👈 PyQt5 系 列 教 程:👉👉 Python GUI(PyQt5)文章合集 👈👈 Oracle数据库教程:👉👉 Oracle数据库文章合集 👈👈 优

如何快速练习键盘盲打

盲打是指在不看键盘的情况下进行打字,这样可以显著提高打字速度和效率。以下是一些练习盲打的方法: 熟悉键盘布局:首先,你需要熟悉键盘上的字母和符号的位置。可以通过键盘图或者键盘贴纸来帮助记忆。 使用在线打字练习工具:有许多在线的打字练习网站,如Typing.com、10FastFingers等,它们提供了不同难度的练习和测试。 练习基本键位:先从学习手指放在键盘上的“家位”开始,通常是左手的

anaconda3下的python编程练习-csv翻译器

相关理解和命令 一、环境配置1、conda命令2、pip命令3、python命令 二、开发思路三、开发步骤 一、环境配置 1、conda命令 镜像源配置 conda config --show channels //查看镜像源conda config --remove-key channels //删除添加源,恢复默认源#添加镜像源conda config --ad