ROS2下YOLO+Moveit+PCL机械臂自主避障抓取方案

整体运行架构

1.运行相机取像节点
. ./install/setup.bash
ros2 launch orbbec_camera gemini_330_series.launch.py depth_registration:=true
2.运行根据图像x,y获取z的service

基本操作记录:

  1. 创建python包,在src目录下
    ros2 pkg create test_python_topic --build-type ament_python --dependencies rclpy --license Apache-2.0
    2.创建service
    ros2 pkg create getzservice --dependencies sensor_msgs rosidl_default_generators --license Apache-2.0

source ~/test_ws/install/setup.bash

一、奥比中光Gemini335相机使用

https://www.orbbec.com.cn/index/Gemini330/info.html?cate=119&id=74
https://github.com/orbbec/OrbbecSDK_v2/releases
1.

cd ~/ros2_ws/
# 构建 Release 版本,默认为 Debug
colcon build --event-handlers  console_direct+  --cmake-args  -DCMAKE_BUILD_TYPE=Release
. ./install/setup.bash
ros2 launch orbbec_camera gemini_330_series.launch.py depth_registration:=true

话题是 /camera/depth_registered/points
得到的图像是sensor_msgs/msg/PointCloud2
ros2 interface show sensor_msgs/msg/PointCloud2 可以看到图像数据格式

. ./install/setup.bash
rviz2

写一个节点

二、YOLO ROS的使用

https://github.com/mgonzs13/yolo_ros/tree/main

终端1:

. ./install/setup.bash
ros2 launch orbbec_camera gemini_330_series.launch.py depth_registration:=true

终端2:

. ./install/setup.bash
ros2 launch yolo_bringup yolo.launch.py input_image_topic:=/camera/color/image_raw  device:=cpu

终端3:

. ./install/setup.bash
ros2 topic info /camera/color/image_raw
rviz2

三、睿尔曼RM65的使用

https://develop.realman-robotics.com/robot/quickUseManual/

快速启动:

colcon build
source ~/ros2_ws/install/setup.bash
ros2 launch rm_bringup rm_65_bringup.launch.py

一个一个启动:

export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/home/zc9527/ros2_ws/src/ros2_rm_robot/rm_driver/lib

ros2 launch rm_driver rm_65_driver.launch.pyros2 launch rm_description rm_65_display.launch.pyros2 launch rm_control rm_65_control.launch.pyros2 launch rm_65_config real_moveit_demo.launch.py

joint_states代表机械臂当前的状态,我们的rm_driver功能包运行时会发布该话题,这样rviz中的模型就会根据实际的机械臂状态进行运动。

rm_control功能包为实现moveit2控制真实机械臂时所必须的一个功能包,该功能包的主要作用为将moveit2规划好的路径点进行进一步的细分,将细分后的路径点以透传的方式给到rm_driver,实现机械臂的规划运行。

rm_description功能包为显示机器人模型和TF变换的功能包,通过该功能包,我们可以实现电脑中的虚拟机械臂与现实中的实际机械臂的联动的效果
/robot_state_publisher

rm_moveit2_config是实现Moveit2控制真实机械臂的功能包,该功能包的主要作用为调用官方的Moveit2框架,结合我们机械臂本身的URDF生成适配于我们机械臂的moveit2的配置和启动文件,通过该功能包我们可以实现moveit2控制虚拟机械臂和控制真实机械臂。
/interactive_marker_display_99263946702096
/move_group
/move_group_private_105684501566768
/moveit_simple_controller_manager
/rviz
/rviz_ssp_robot_description
/transform_listener_impl_5a47b008a910
/transform_listener_impl_601e972d1ab0

ros2 run rqt_graph rqt_graph
节点关系图
rm_control/rm_control
rm_description/robot_state_publisher
rm_65_config /moveit_simple_controller_manager
rm_65_config //transform_listener_impl

ompl_planning不会自动生成,需要自己添加文件内容如下:

planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-default_planner_request_adapters/AddTimeOptimalParameterizationdefault_planner_request_adapters/ResolveConstraintFramesdefault_planner_request_adapters/FixWorkspaceBoundsdefault_planner_request_adapters/FixStartStateBoundsdefault_planner_request_adapters/FixStartStateCollisiondefault_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
planner_configs:SBLkConfigDefault:type: geometric::SBLrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()ESTkConfigDefault:type: geometric::ESTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05LBKPIECEkConfigDefault:type: geometric::LBKPIECErange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5BKPIECEkConfigDefault:type: geometric::BKPIECErange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5KPIECEkConfigDefault:type: geometric::KPIECErange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9 (0.0,1.]failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5RRTkConfigDefault:type: geometric::RRTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05RRTConnectkConfigDefault:type: geometric::RRTConnectrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()RRTstarkConfigDefault:type: geometric::RRTstarrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05delay_collision_checking: 1  # Stop collision checking as soon as C-free parent found. default 1TRRTkConfigDefault:type: geometric::TRRTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05max_states_failed: 10  # when to start increasing temp. default: 10temp_change_factor: 2.0  # how much to increase or decrease temp. default: 2.0min_temperature: 10e-10  # lower limit of temp change. default: 10e-10init_temperature: 10e-6  # initial temperature. default: 10e-6frountier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()frountierNodeRatio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1k_constant: 0.0  # value used to normalize expresssion. default: 0.0 set in setup()PRMkConfigDefault:type: geometric::PRMmax_nearest_neighbors: 10  # use k nearest neighbors. default: 10PRMstarkConfigDefault:type: geometric::PRMstarFMTkConfigDefault:type: geometric::FMTnum_samples: 1000  # number of states that the planner should sample. default: 1000radius_multiplier: 1.1  # multiplier used for the nearest neighbors search radius. default: 1.1nearest_k: 1  # use Knearest strategy. default: 1cache_cc: 1  # use collision checking cache. default: 1heuristics: 0  # activate cost to go heuristics. default: 0extended_fmt: 1  # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1BFMTkConfigDefault:type: geometric::BFMTnum_samples: 1000  # number of states that the planner should sample. default: 1000radius_multiplier: 1.0  # multiplier used for the nearest neighbors search radius. default: 1.0nearest_k: 1  # use the Knearest strategy. default: 1balanced: 0  # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1optimality: 1  # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1heuristics: 1  # activates cost to go heuristics. default: 1cache_cc: 1  # use the collision checking cache. default: 1extended_fmt: 1  # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1PDSTkConfigDefault:type: geometric::PDSTSTRIDEkConfigDefault:type: geometric::STRIDErange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05use_projected_distance: 0  # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0degree: 16  # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16max_degree: 18  # max degree of a node in the GNAT. default: 12min_degree: 12  # min degree of a node in the GNAT. default: 12max_pts_per_leaf: 6  # max points per leaf in the GNAT. default: 6estimated_dimension: 0.0  # estimated dimension of the free space. default: 0.0min_valid_path_fraction: 0.2  # Accept partially valid moves above fraction. default: 0.2BiTRRTkConfigDefault:type: geometric::BiTRRTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()temp_change_factor: 0.1  # how much to increase or decrease temp. default: 0.1init_temperature: 100  # initial temperature. default: 100frountier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()frountier_node_ratio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1cost_threshold: 1e300  # the cost threshold. Any motion cost that is not better will not be expanded. default: infLBTRRTkConfigDefault:type: geometric::LBTRRTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05epsilon: 0.4  # optimality approximation factor. default: 0.4BiESTkConfigDefault:type: geometric::BiESTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()ProjESTkConfigDefault:type: geometric::ProjESTrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05LazyPRMkConfigDefault:type: geometric::LazyPRMrange: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()LazyPRMstarkConfigDefault:type: geometric::LazyPRMstarSPARSkConfigDefault:type: geometric::SPARSstretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001max_failures: 1000  # maximum consecutive failure limit. default: 1000SPARStwokConfigDefault:type: geometric::SPARStwostretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001max_failures: 5000  # maximum consecutive failure limit. default: 5000TrajOptDefault:type: geometric::TrajOptrm_group:planner_configs:- SBLkConfigDefault- ESTkConfigDefault- LBKPIECEkConfigDefault- BKPIECEkConfigDefault- KPIECEkConfigDefault- RRTkConfigDefault- RRTConnectkConfigDefault- RRTstarkConfigDefault- TRRTkConfigDefault- PRMkConfigDefault- PRMstarkConfigDefault- FMTkConfigDefault- BFMTkConfigDefault- PDSTkConfigDefault- STRIDEkConfigDefault- BiTRRTkConfigDefault- LBTRRTkConfigDefault- BiESTkConfigDefault- ProjESTkConfigDefault- LazyPRMkConfigDefault- LazyPRMstarkConfigDefault- SPARSkConfigDefault- SPARStwokConfigDefault- TrajOptDefault

moveL运动:
ros2 launch rm_driver rm_65_driver.launch.py
ros2 launch rm_example rm_6dof_movej.launch.py

四、moveit2的使用

https://github.com/moveit/moveit2_tutorials/tree/humble
https://blog.csdn.net/forever0007/article/details/143745333
https://zhuanlan.zhihu.com/p/616101551

五、moveit2和睿尔曼机器人的联合使用

ros2 pkg create \--build-type ament_cmake \--dependencies moveit_ros_planning_interface rclcpp \--node-name hello_moveit hello_moveit
source install/setup.bash
ros2 run hello_moveit hello_moveit

最简单使用

#include <memory>#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>int main(int argc, char* argv[])
{// Initialize ROS and create the Noderclcpp::init(argc, argv);auto const node = std::make_shared<rclcpp::Node>("hello_moveit", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));// Create a ROS loggerauto const logger = rclcpp::get_logger("hello_moveit");// Create the MoveIt MoveGroup Interfaceusing moveit::planning_interface::MoveGroupInterface;auto move_group_interface = MoveGroupInterface(node, "rm_group");// Set a target Poseauto const target_pose = [] {geometry_msgs::msg::Pose msg;msg.orientation.w = 1.0;msg.position.x = 0.28;msg.position.y = -0.2;msg.position.z = 0.5;return msg;}();move_group_interface.setPoseTarget(target_pose);// Create a plan to that target poseauto const [success, plan] = [&move_group_interface] {moveit::planning_interface::MoveGroupInterface::Plan msg;auto const ok = static_cast<bool>(move_group_interface.plan(msg));return std::make_pair(ok, msg);}();// Execute the planif (success){move_group_interface.execute(plan);}else{RCLCPP_ERROR(logger, "Planing failed!");}// Shutdown ROSrclcpp::shutdown();return 0;
}

六、ROS2 PCL的使用

https://github.com/adrian-soch/pcl_tutorial?utm_source=chatgpt.com

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。
如若转载,请注明出处:http://www.pswp.cn/pingmian/94011.shtml
繁体地址,请注明出处:http://hk.pswp.cn/pingmian/94011.shtml

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

快速入门Vue3——初体验

目录 前言 一、搭建环境 1.1、安装Node.js 1.2、安装Vite 二、项目创建 三、运行项目 四、集成Pinia 4.1、Pinia介绍 4.2、Pinia安装 五、集成VueUse 5.1、vueuse简介 5.2、vueuse安装 六、集成Vant 6.1、Vant简介 6.2、Vant安装 前言 本专栏主要介绍如何使用…

深入理解Kubernetes核心:标签与标签选择器实战解析

在管理 Kubernetes 集群时&#xff0c;随着 Pods、Services 等资源数量的增长&#xff0c;如何有效地组织和筛选它们&#xff0c;成为了一个核心问题。Kubernetes 为此提供了一个简单却极其强大的机制&#xff1a;标签&#xff08;Labels&#xff09;和标签选择器&#xff08;L…

哈希和字符串哈希

哈希&#xff08;Hash&#xff09; Hash 表 Hash 表又称为散列表&#xff0c;一般由 Hash 函数&#xff08;散列函数&#xff09;与链表结构共同实现。与离散化思想类似&#xff0c;当我们要对若干复杂信息进行统计时&#xff0c;可以用 Hash 函数把这些复杂信息映射到一个容…

【Docker基础】Docker-Compose核心配置文件深度解析:从YAML语法到高级配置

目录 前言 1 YAML基础语法解析 1.1 YAML格式简介 1.2 Docker-compose中的YAML语法规则 1.3 YAML数据类型在Compose中的应用 2 docker-compose.yml文件结构剖析 2.1 基本文件结构 2.2 版本声明详解 3 services配置深度解析 3.1 服务定义基础 3.2 镜像与构建配置 3.3…

如何判断是否应该为了一个小功能而引入一个大体积的库

在软件开发中&#xff0c;判断是否应该为了一个看似微小的功能&#xff0c;而引入一个大体积的第三方库&#xff0c;是一项极其重要的、需要进行审慎的“投入产出比”分析的技术决策。这个决策&#xff0c;绝不能&#xff0c;仅仅基于“实现功能的便利性”&#xff0c;而必须&a…

相机定屏问题分析五:【跳帧异常】照片模式1x以上的焦段拍照之后定屏

【关注我&#xff0c;后续持续新增专题博文&#xff0c;谢谢&#xff01;&#xff01;&#xff01;】 上一篇我们讲了&#xff1a; 这一篇我们开始讲&#xff1a; 相机定屏问题分析五&#xff1a;【跳帧异常】照片模式1x以上的焦段拍照之后定屏9573412 目录 一、问题背景 二…

Non-stationary Diffusion For Probabilistic Time Series Forecasting论文阅读笔记

Non-stationary Diffusion For Probabilistic Time Series Forecasting 摘要 时间序列数据受到潜在的物理动力学和外部影响&#xff0c;其不确定性通常随时间而变化。现有的去噪扩散概率模型&#xff08;DDPMs&#xff09;受到加性噪声模型&#xff08;ANM&#xff09;的恒定方…

解决Docker 无法连接到官方镜像仓库

这个错误&#xff1a; Error response from daemon: Get "https://registry-1.docker.io/v2/": net/http: request canceled while waiting for connection (Client.Timeout exceeded while awaiting headers)表示 Docker 无法连接到官方镜像仓库 registry-1.docker…

解决RAGFlow启动时Elasticsearch容器权限错误的技术指南

文章目录 问题现象 根本原因分析 解决方案步骤 1. 定位宿主机数据目录 2. 修复目录权限 3. 验证权限状态 4. 重启服务 5. 检查启动状态 永久解决方案:优化Docker Compose配置 高级故障排除 技术原理 问题现象 在启动RAGFlow项目时,执行 docker logs ragflow-es-01 发现Elast…

【C++高阶六】哈希与哈希表

【C高阶六】哈希与哈希表1.什么是哈希&#xff1f;2.unordered系列容器3.哈希表3.1将key与存储位置建立映射关系3.1.1直接定址法3.1.2除留余数法&#xff08;产生哈希冲突&#xff09;3.2解决哈希冲突的方法3.2.1闭散列&#xff08;开放定址法&#xff09;3.3.2开散列&#xff…

Vue 3 +Ant Design Vue 父容器样式不影响子级,隔离

公共样式文件 common.scss.zz-ant-status-bar {div {font-size: 12px;padding: 0 8px;} }页面代码<div class"zz-ant-status-bar"><a-row><a-col :span"6" ><a-progress :percent"progress.percent" size"small"…

k8s 简介及部署方法以及各方面应用

Kubernetes 简介及部署方法Kubernetes&#xff08;简称 K8s&#xff09;是一个开源的容器编排平台&#xff0c;用于自动化容器化应用的部署、扩展、管理和运维。它由 Google 基于内部的 Borg 系统经验开发&#xff0c;2014 年开源后由云原生计算基金会&#xff08;CNCF&#xf…

Class A 包含字段 x Class B 也包含字段 x,如果判断List<A> lista 和 List<B> listb 有相同的 x?

要判断两个不同类型的对象列表 List<A> 和 List<B> 是否包含相同的 x字段值&#xff08;即两个列表中至少有一个 x是相同的&#xff09;&#xff0c;你可以使用 Java 8 的 Stream API 来实现。import java.util.List; import java.util.Set; import java.util.stre…

SpringBoot整合Camunda工作流

什么是工作流&#xff1f;概述 工作流是将一组任务组织起来以完成某个经营过程&#xff1a;定义了任务的触发顺序和触发条件&#xff0c;每个任务可以由一个或多个软件系统完成&#xff0c;也可以由一个或一组人完成&#xff0c;还可以由一个或多个人与软件系统协作完成&#x…

2025年09月计算机二级Java选择题每日一练——第四期

计算机二级中选择题是非常重要的&#xff0c;所以开始写一个每日一题的专栏。 答案及解析将在末尾公布&#xff01; 今日主题&#xff1a;面向对象特性 1、有两个类 A 和 B 的定义如下&#xff1a; class A{final int x10;public void show(){System.out.print(x " &quo…

《Nature》新文解读:电化学辅助核聚变的实验验证与机制分析

前言一篇于2025年8月发表在《Nature》期刊上的重磅研究&#xff0c;由加拿大不列颠哥伦比亚大学&#xff08;UBC&#xff09;Curtis P. Berlinguette教授领导的跨学科团队完成&#xff0c;首次在实验上证实&#xff1a;通过电化学方法向钯金属靶中加载氘&#xff0c;可显著提升…

【基础-判断】用户在长视频、短视频、直播、通话、会议、拍摄类应用等场景下,可以采用悬停适配在折叠屏半折态时,上屏进行浏览下屏进行交互操作

用户在长视频、短视频、直播、通话、会议、拍摄类应用等场景下,可以采用悬停适配在折叠屏半折态时,上屏进行浏览下屏进行交互操作。 解释如下: ✅ 1. 悬停态适配机制的核心设计 HarmonyOS 针对折叠屏半折态(悬停态)提供了分屏交互框架,其核心逻辑是: 上屏(Upper Scre…

nodejs安装后 使用npm 只能在cmd 里使用 ,但是不能在poowershell使用,只能用npm.cmd

nodejs安装后 使用npm 只能在cmd 里使用 &#xff0c;但是不能在poowershell使用&#xff0c;只能用npm.cmdnodejs版本&#xff1a;22.18.0 刚安装好nodejs&#xff0c;在 PowerShell 中无法执行 npm&#xff0c;但能执行npm.cmd&#xff0c;这通常是因为 PowerShell 的执行策略…

【链表 - LeetCode】2. 两数相加

谁都逃不掉 LeetCode &#xff01;&#xff01;哈哈哈~~~ 开刷&#xff1a;&#xff09; 2025年08月22日 题目&#xff1a;2. 两数相加 - 力扣&#xff08;LeetCode&#xff09; 知识点&#xff1a;链表 /*** Definition for singly-linked list.* struct ListNode {* in…

WG-Tools 在线开发者工具推荐:完全免费、无广告干扰、无需安装、即开即用

WG-Tools 在线开发者工具箱全面探秘: 一站式效率提升平台前言一. WG-Tools 平台介绍 &#x1f6e0;️平台概览技术架构亮点二. 功能模块详细介绍 &#x1f3af;&#x1f4dd; 文本处理工具 (Text Tools)1. JSON工具2. XML工具3. 文本对比4. 正则表达式工具5. Markdown编辑器6. …