当前位置: 首页 > news >正文

撰写脚本,通过发布/joint_states话题改变机器人在Rviz中的关节角度

撰写脚本,通过发布/joint_states话题改变机器人在Rviz中的关节角度

提问

为我写一个改变关节base_spherical_center_high_joint角度的python脚本吧。适用于ROS2的humble

回答

下面是一个适用于 ROS 2 Humble 的 Python 脚本,它会以指定频率持续发布 base_spherical_center_high_joint 的角度到 /joint_states,从而驱动 robot_state_publisher 正常广播 TF。


publish_joint_angle.py

#!/usr/bin/env python3import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from builtin_interfaces.msg import Time
import mathclass JointPublisher(Node):def __init__(self):super().__init__('joint_state_publisher_node')self.publisher_ = self.create_publisher(JointState, '/joint_states', 10)# Timer: 10Hzself.timer = self.create_timer(0.1, self.publish_joint_state)# Desired joint position (radians)self.joint_position = 1.5708  # 90 degreesdef publish_joint_state(self):msg = JointState()msg.header.stamp = self.get_clock().now().to_msg()msg.name = ['base_spherical_center_high_joint']msg.position = [self.joint_position]self.publisher_.publish(msg)self.get_logger().info(f'Publishing: {msg.name[0]} = {self.joint_position:.4f} rad')def main(args=None):rclpy.init(args=args)node = JointPublisher()rclpy.spin(node)node.destroy_node()rclpy.shutdown()if __name__ == '__main__':main()

✅ 使用说明:

  1. 保存为 publish_joint_angle.py
  2. 给脚本加执行权限:
chmod +x publish_joint_angle.py
  1. 运行脚本(建议在 ROS2 工作空间中):
ros2 run <your_package_name> publish_joint_angle

或在独立目录中运行:

python3 publish_joint_angle.py

需要我帮你把它打包成 ROS2 可执行节点(添加到 setup.pyentry_points)吗?

继续提问

可以帮我添加。直接在这个基础上修改:
setup(
name=package_name,
version=‘0.0.0’,
packages=find_packages(exclude=[‘test’]),
# data_files=[
# (‘share/ament_index/resource_index/packages’,
# [‘resource/’ + package_name]),
# (‘share/’ + package_name, [‘package.xml’]),
# ],
data_files = data_files_list,
install_requires=[‘setuptools’],
zip_safe=True,
maintainer=‘usv-6081’,
maintainer_email=‘usv-6081@todo.todo’,
description=‘TODO: Package description’,
license=‘TODO: License declaration’,
tests_require=[‘pytest’],
entry_points={
‘console_scripts’: [
‘hello_node = control_planner.hello_node:main’,
‘usv_Simulation = control_planner.usvSimV2:main’,
‘keyboard_interaction = control_planner.keyboard_interaction:main’,
],
},
)

回答

当然可以!你只需要将新的脚本添加到 entry_points['console_scripts'] 列表中,并确保你的 Python 文件(如 publish_joint_angle.py)位于包内模块路径 control_planner/ 下,并包含 main() 函数。


✅ 修改后的 setup.py 示例(新增 publish_joint_angle 入口):

setup(name=package_name,version='0.0.0',packages=find_packages(exclude=['test']),data_files=data_files_list,install_requires=['setuptools'],zip_safe=True,maintainer='usv-6081',maintainer_email='usv-6081@todo.todo',description='TODO: Package description',license='TODO: License declaration',tests_require=['pytest'],entry_points={'console_scripts': ['hello_node = control_planner.hello_node:main','usv_Simulation = control_planner.usvSimV2:main','keyboard_interaction = control_planner.keyboard_interaction:main','publish_joint_angle = control_planner.publish_joint_angle:main',  # 新增这一行],},
)

✅ 注意事项:

  1. publish_joint_angle.py 文件要放在 control_planner/ 目录中(和其他 .py 文件一样)。

  2. 文件中必须包含:

    if __name__ == '__main__':main()
    

    并有 main() 函数定义。

  3. 别忘了在工作区根目录执行构建命令:

    colcon build
    source install/setup.bash
    

然后你就可以直接运行这个脚本:

ros2 run control_planner publish_joint_angle

需要我帮你检查 publish_joint_angle.py 是否需要加入 __init__.py 或补充模块结构吗?

结果

成功

http://www.xdnf.cn/news/903835.html

相关文章:

  • HakcMyVM -TheWall
  • 初识AI Agent
  • 面向开发者的提示词工程④——文本推断(Inferring)
  • 数学建模期末速成 聚类分析与判别分析
  • Caliper 配置文件解析:fisco-bcos.json
  • 【计算机组成原理 第5版】白、戴编著 第六章 总线系统 课后题总结
  • 大模型安全测试报告:千问、GPT 全系列、豆包、Claude 表现优异,DeepSeek、Grok-3 与 Kimi 存在安全隐患
  • LabVIEW工业级多任务实时测控系统
  • ComfyUI 文生图教程,进行第一次的图片生成
  • 连续小波变换(Continuous Wavelet Transform, CWT)
  • 【HarmonyOS 5】出行导航开发实践介绍以及详细案例
  • Spring Boot实现接口时间戳鉴权
  • ABAP设计模式之---“简单设计原则(Simple Design)”
  • Windows无限期暂停更新
  • 模板方法模式:优雅封装不变,灵活扩展可变
  • web3-基于贝尔曼福特算法(Bellman-Ford )与 SMT 的 Web3 DeFi 套利策略研究
  • 贝叶斯深度学习!华科大《Nat. Commun.》发表BNN重大突破!
  • Science Robotics:UCLA 贺曦敏团队综述自主软体机器人
  • dexcap升级版之DexWild——面向户外环境的灵巧手交互策略:人类和机器人演示协同训练(人类直接带上动捕手套采集数据)
  • 【Linux 学习计划】-- 简易版shell编写
  • 【大模型LLM学习】Flash-Attention的学习记录
  • 阿里140 补环境日志
  • 华为 “一底双长焦” 专利公布,引领移动影像新变革
  • Caliper 负载(Workload)详细解析
  • 【NLP中向量化方式】序号化,亚编码,词袋法等
  • MySQL数据库基础(二)———数据表管理
  • 安卓基础(生成APK)
  • React 第五十六节 Router 中useSubmit的使用详解及注意事项
  • next,react封装axios,http请求
  • ✅ 常用 Java HTTP 客户端汇总及使用示例