diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/LICENSE b/HiveCoreR0/src/ros2_rm_robot-humble/LICENSE new file mode 100644 index 0000000..0ef8650 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/LICENSE @@ -0,0 +1,13 @@ +Copyright 2024 realman-robotics + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/README.md new file mode 100644 index 0000000..74605f4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/README.md @@ -0,0 +1,175 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/README_CN.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/README.md) + +
+ +# ros2_rm_robot + +The package is mainly used for providing ROS2 support for the robotic arm, and the following is the use environment. + +* Currently supported robotic arms are RM65 series, RM75 series, ECO65 series, ECO63 series, RML63 series, GEN72 series, and the details can be referred to the website [RealMan robots](http://www.realman-robotics.com/). +* Version V1.5.0. +* The supported robotic arm controller version is 1.4.3 or above. +* The Ubuntu version is 22.04. +* The ROS2 version is humble. + +The following is the installation and use tutorial of the package. + +## 1\. Build the environment +--- +Before using the package, we first need to do the following operations. + +* 1.[Install ROS2](#1.Install_ROS2) +* 2.[Install Moveit2](#Install_Moveit2) +* 3.[Configure the package environment](#Configure_the_package_environment) +* 4.[Compile](#Compile) + +### 1.Install_ROS2 + +---- + +We provide the installation script for ROS2, ros2_install.sh, which is located in the scripts folder of the rm_install package. In practice, we need to move to the path and execute the following commands. + +``` +sudo bash ros2_install.sh +``` + +If you do not want to use the script installation, you can also refer to the website [ROS2_INSTALL](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). + +### Install_Moveit2 + +---- + +We provide the installation script for Moveit2, moveit2_install.sh, which is located in the scripts folder of the rm_install package. In practice, we need to move to the path and execute the following commands. + +``` +sudo bash moveit2_install.sh +``` + +If you do not want to use the script installation, you can also refer to the website [Moveit2_INSTALL](https://moveit.ros.org/install-moveit2/binary/). + +### Configure_the_package_environment + +---- + +This script is located in the lib folder of the rm_driver package. In practice, we need to move to the path and execute the following commands. + +``` +sudo bash lib_install.sh +``` + +### Compile + +---- + +After the above execution is successful, execute the following commands to compile the package. First, we need to build a workspace and import the package file into the src folder under the workspace, and then use the colcon build command to compile. + +``` +mkdir -p ~/ros2_ws/src +cp -r ros2_rm_robot ~/ros2_ws/src +cd ~/ros2_ws +colcon build --packages-select rm_ros_interfaces +source ./install/setup.bash +colcon build +``` + +After the compilation is completed, the package can be run. + +## 2\. Function running + +--- + +Package introduction + +1. Installation and environment configuration ([rm_install](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_install)) + +* This package is the auxiliary package for using the robotic arm. It is mainly used to introduce the installation and construction method of the package use environment, the installation of the dependent library and the compilation method of the function package. + +3. Hardware driver ([rm_driver](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_driver)) + +* This package is the ROS2 underlying driver package of the robotic arm. It is used to subscribe and publish the underlying related topic information of the robotic arm. + +5. Launch ([rm_bringup](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_bringup)) + +* This package is the node launch package of the robotic arm. It is used to quickly launch the multi-node compound robotic arm function. + +6. Model description ([rm_description](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_description)) + +* This package is the model description package of the robotic arm. It is used to provide the robotic arm model file and model load node, and provide the coordinate transformation relationship between the joints of the robotic arm for other packages. + +7. ROS message interface ([rm_ros_interfaces](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_ros_interfaces)) + +* This package is the message file package of the robotic arm. It is used to provide all control messages and state messages for the robotic arm to adapt to ROS2. + +8. Moveit2 configuration [(rm_moveit2_config](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_moveit2_config) + +* This package is the moveit2 adaptation package of the robotic arm. It is used to adapt and realize the moveit2 planning and control functions of various series of robotic arms, mainly including the control functions of virtual robotic arm control and real robotic arm control. + +9. Moveit2 and hardware driver communication connection ([rm_config](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_control)) + +* This package is the communication connection package between the underlying driver package (rm_driver) and the moveit2 package (rm_moveit2_config). It is mainly used to subdivide the planning points of moveit2 and then pass them to the underlying driver package in the form of transmission to control the motion of the robotic arm. + +10. Gazebo simulation robotic arm control ([rm_gazebo](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_gazebo)) + +* This package is the gazebo simulation robotic arm package. It is mainly used to display the robotic arm model in the gazebo simulation environment, and the planning and control of the simulated robotic arm can be carried out through moveit2. + +11. Use examples ([rm_examples](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_example)) + +* This package is some use examples of the robotic arm, and it is mainly used to realize some basic control functions and motion functions of the robotic arm. + +12. Technical documentation ([rm_docs](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_doc)) + +* This package is an introduction document package, which mainly includes a document that provides an overall introduction to the content and usage of the packages, as well as a document that provides a detailed introduction to the content and usage of each package. + +The above are the current ten packages; each package has its own unique role. Please refer to the document in the doc folder under the rm_doc package for a detailed understanding. + +### 2.1 Run the virtual robotic arm + +---- + +Use the following command to launch the gazebo to display the simulation robotic arm, and launch moveit2 for the planning and control of the simulation robotic arm. + +``` +source ~/ros2_ws/install/setup.bash +ros2 launch rm_bringup rm__gazebo.launch.py +``` + +\ needs to use 65, 75, eco65、eco63, 63, gen72, gen72_II characters to replace it. For example, when using an RM65 robotic arm, the command is as follows. + +``` +ros2 launch rm_bringup rm_65_gazebo.launch.py +``` + +After successful launch, you can use moveit2 for the control of the virtual robotic arm. + +### 2.2 Control the real robotic arm + +---- + +Use the following command to launch the hardware driver of the robotic arm, and launch moveit2 for the planning and control of the robotic arm. + +``` +source ~/ros2_ws/install/setup.bash +ros2 launch rm_bringup rm__bringup.launch.py +``` + +\ needs to use 65, 75, eco65、eco63, 63, gen72, gen72_II characters to replace it. For example, when using an RM65 robotic arm, the command is as follows. + +``` +ros2 launch rm_bringup rm_65_bringup.launch.py +``` + +After successful launch, you can use moveit2 for the control of the real robotic arm. + +### Safety Tips + +---- + +Please refer to the following operation specifications when using the robotic arm to ensure the user's safety. + +* Check the installation of the robotic arm before each use, including whether the mounting screw is loose and whether the robotic arm is vibrating or trembling. +* During the running of the robotic arm, no person shall be in the falling or working range of the robotic arm, nor shall any other object be placed in the robot arm's safety range. +* Place the robotic arm in a safe location when not in use to avoid it from falling down and damaging or injuring other objects during vibration. +* Disconnect the robotic arm from the power supply in time when not in use. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/README_CN.md new file mode 100644 index 0000000..e63d136 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/README_CN.md @@ -0,0 +1,113 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/README_CN.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/README.md) + +
+ +# ros2_rm_robot +该功能包的主要作用为提供机械臂的ROS2支持,以下为使用环境。 +* 当前支持的机械臂有RM65系列、RM75系列、ECO65系列、ECO63系列、RML63系列、GEN72系列,详细可参考网址 [RealMan robots](http://www.realman-robotics.com/)。 +* 版本1.5.0. +* 支持的机械臂控制器版本1.4.3以上。 +* 基于的Ubuntu版本为22.04。 +* ROS2版本为humble。 + +下面为功能包安装使用教程。 +## 1.搭建环境 +--- +在使用功能包之前我们首先需要进行如下操作。 +* 1.[安装ROS2](#安装ROS2) +* 2.[安装Moveit2](#安装Moveit2) +* 3.[配置功能包环境](#配置功能包环境) +* 4.[编译](#编译) +### 安装ROS2 +---- +我们提供了ROS2的安装脚本ros2_install.sh,该脚本位于rm_install功能包中的scripts文件夹下,在实际使用时我们需要移动到该路径执行如下指令。 +``` +sudo bash ros2_install.sh +``` +如果不想使用脚本安装也可以参考网址 [ROS2_INSTALL](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html)。 +### 安装Moveit2 +---- +我们提供了Moveit2的安装脚本moveit2_install.sh,该脚本位于rm_install功能包中的scripts文件夹下,在实际使用时我们需要移动到该路径执行如下指令。 +``` +sudo bash moveit2_install.sh +``` +如果不想使用脚本安装也可以参考网址 [Moveit2_INSTALL](https://moveit.ros.org/install-moveit2/binary/)进行安装。 +### 配置功能包环境 +---- +该脚本位于rm_driver功能包中的lib文件夹下,在实际使用时我们需要移动到该路径执行如下指令。 +``` +sudo bash lib_install.sh +``` +### 编译 +---- +以上执行成功后,可以执行如下指令进行功能包编译,首先需要构建工作空间,并将功能包文件导入工作空间下的src文件夹下,之后使用colcon build指令进行编译。 +``` +mkdir -p ~/ros2_ws/src +cp -r ros2_rm_robot ~/ros2_ws/src +cd ~/ros2_ws +colcon build --packages-select rm_ros_interfaces +source ./install/setup.bash +colcon build +``` +编译完成后即可进行功能包的运行操作。 + + +## 2.功能运行 +--- +功能包简介 +1. 安装与环境配置([rm_install](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_install)) +* 该功能包为机械臂使用辅助功能包,主要作用为介绍功能包使用环境安装与搭建方式,功能包的依赖库安装和功能包编译方法。 +3. 硬件驱动([rm_driver](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_driver)) +* 该功能包为机械臂的ROS2底层驱动功能包,其作用为订阅和发布机械臂底层相关话题信息。 +5. 启动([rm_bringup](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_bringup)) +* 该功能包为机械臂的节点启动功能包,其作用为快速启动多节点复合的机械臂功能。 +6. 模型描述([rm_description](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_description)) +* 该功能包为机械臂模型描述功能包,其作用为提供机械臂模型文件和模型加载节点,并为其他功能包提供机械臂关节间的坐标变换关系。 +7. ROS消息接口([rm_ros_interfaces](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_ros_interfaces)) +* 该功能包为机械臂的消息文件功能包,其作用为提供机械臂适配ROS2的所有控制消息和状态消息。 +8. Moveit2配置([rm_moveit2_config](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_moveit2_config)) +* 该功能包为机械臂的moveit2适配功能包,其作用为适配和实现各系列机械臂的moveit2规划控制功能,主要包括虚拟机械臂控制和真实机械臂控制两部分控制功能。 +9. Moveit2与硬件驱动通信连接([rm_config](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_control)) +* 该功能包为底层驱动功能包(rm_driver)和moveit2功能包(rm_moveit2_config)之间的通信连接功能包,主要功能为将moveit2的规划点进行细分然后通过透传的形式传递给底层驱动功能包控制机械臂运动。 +10. Gazebo仿真机械臂控制([rm_gazebo](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_gazebo)) +* 该功能包为gazebo仿真机械臂功能包,主要功能为在gazebo仿真环境中显示机械臂模型,可通过moveit2对仿真的机械臂进行规划控制。 +11. 使用案例([rm_examples](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_example)) +* 该功能包为机械臂的一些使用案例,主要功能为实现机械臂的一些基本的控制功能和运动功能的使用案例。 +12. 技术文档([rm_docs](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_doc)) +* 该功能包为介绍文档的功能包,其主要包括为对整体的功能包内容和使用方式进行总体介绍的文档和对每个功能包中的内容和使用方式进行详细介绍的文档。 + +以上为当前的十个功能包,每个功能包都有其独特的作用,详情请参考rm_doc功能包下的doc文件夹中的文档进行详细了解。 +### 2.1运行虚拟机械臂 +---- +使用如下指令可以启动gazebo显示仿真机械臂,并同时启动moveit2进行仿真机械臂的规划操控。 +``` +source ~/ros2_ws/install/setup.bash +ros2 launch rm_bringup rm__gazebo.launch.py +``` +需要使用65、75、eco65、eco63、63、gen72、gen72_II字符进行代替,如使用RM65机械臂时,命令如下。 +``` +ros2 launch rm_bringup rm_65_gazebo.launch.py +``` +启动成功后即可使用moveit2进行虚拟机械臂的控制。 +### 2.2控制真实机械臂 +---- +使用如下指令可以启动机械臂硬件驱动,并同时启动moveit2进行机械臂的规划操控。 +``` +source ~/ros2_ws/install/setup.bash +ros2 launch rm_bringup rm__bringup.launch.py +``` +需要使用65、75、eco65、eco63、63、gen72字符进行代替,如使用RM65机械臂时,命令如下。 +``` +ros2 launch rm_bringup rm_65_bringup.launch.py +``` +启动成功后即可使用moveit2进行真实机械臂的控制。 +### 安全提示 +---- +在使用机械臂时,为保证使用者安全,请参考如下操作规范。 +* 每次使用前检查机械臂的安装情况,包括固定螺丝是否松动,机械臂是否存在震动、晃动的情况。 +* 机械臂在运行过程中,人不可处于机械臂落下或工作范围内,也不可将其他物体放到机械臂动作的安全范围内。 +* 在不使用机械臂时,应将机械臂置于安全位置,防止震动时机械臂跌落而损坏或砸伤其他物体。 +* 在不使用机械臂时应及时断开机械臂电源。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/CMakeLists.txt new file mode 100755 index 0000000..7c384a5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 3.8) +project(control_arm_move) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + set(ament_cmake_copyright_FOUND TRUE) + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +add_executable(move_demo src/api_Move_demo.cpp) + +ament_target_dependencies(move_demo rclcpp std_msgs rm_ros_interfaces) + + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME}) + +install(TARGETS +move_demo + DESTINATION lib/${PROJECT_NAME}) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/LICENSE b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/LICENSE new file mode 100644 index 0000000..473abff --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/LICENSE @@ -0,0 +1,13 @@ +Copyright 2024 realman-robotics + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/README.md new file mode 100644 index 0000000..004140f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/README.md @@ -0,0 +1,219 @@ +# 机械臂运动控制`ARM_MOVE_DEMO` + +--- + +## 1.项目介绍 + +本项目是一个基于RM65、RM75机械臂和ROS功能包实现MoveJ、MoveJ_P、MoveL、MoveC规划运动功能,在程序执行时将依次执行关节运动MoveJ指令,位姿运动MoveJ_P指令、直线运动MoveL指令,圆弧运动MoveC指令,在执行成功或失败时终端都会收到相关提示,目的是使ROS开发者迅速掌握并灵活运用机械臂。 + +## 2.代码结构 + +``` +├── CMakeLists.txt <-CMake编译文件 +├── launch <-启动文件夹 +│   ├── rm_65_move.launch.py <-启动文件(RM65) +│   └── rm_75_move.launch.py <-启动文件(RM75) +├── LICENSE <-版本说明 +├── package.xml <-依赖描述文件夹 +├── README.md <-说明文档 +└── src <-C++源码文件夹 + └── api_Move_demo.cpp <-源码文件 +``` + +## 3.项目下载 + +通过项目链接下载本项目工程文件到本地:[ros2_rm_robot](https://github.com/RealManRobot/ros2_rm_robot/tree/humble) + +## 4.环境配置 + +| 项目 | 内容 | +| :-- | :-- | +| 系统 | Ubuntu22.04 | +| ROS版本 | humble | +| 依赖 | 机械臂的ROS2-humble功能包 | + +**配置过程** + +1. 首先需要准备好Ubuntu22.04操作系统的虚拟机或其他设备。 +2. 安装ROS2环境[humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html),也可参考ROS2-humble功能包中的安装说明进行安装。 +3. ROS2-Humble功能包安装 + + 新建工作空间和src文件 + ``` + mkdir -p ~/ros2_ws/src + ``` + + 将ROS2文件放入src中 + ``` + cp -r ros2_rm_robot ~/ros2_ws/src + ``` + + 进入工作空间 + ``` + cd ~/ros2_ws + ``` + + 编译rm_ros_interfaces功能包 + ``` + colcon build --packages-select rm_ros_interfaces + ``` + 声明环境变量 + ``` + source ./install/setup.bash + ``` + + 编译所有功能包 + ``` + colcon build + ``` + + 再次声明环境变量 + ``` + source ./install/setup.bash + ``` + +## 5.使用指南 + +* **命令行使用**: + + 我们需要在一个终端中启动机械臂的rm_driver功能包。 + + ``` + ros2 launch rm_driver rm__driver.launch.py + ``` + + 可以为65、63、eco65、75、gen72,可对照自己使用的设备进行实际选择 + 若我们的机械臂为RM65机械臂时应使用如下启动指令。 + + ``` + ros2 launch control_arm_move rm_65_move.launch.py + ``` + + 若为RM75机械臂时应使用如下启动指令。 + + ``` + ros2 launch control_arm_move rm_75_move.launch.py + ``` + + > 若非RM65、RM75机械臂可能会出现无法到达点位的情况,为正常现象。 + +* **返回信息**: + + 在程序成功运行时将会出现以下提示信息。 + ``` + [move_demo-1] [INFO] [1722921182.157890965] [Move_demo_pub_node]: arm_dof is 7 //当前控制机械臂自由度提示 + [move_demo-1] + [move_demo-1] [INFO] [1722921188.120872813] [Move_demo_sub_node]: *******Movej succeeded //MoveJ运动成功时的提示信息 + [move_demo-1] + [move_demo-1] [INFO] [1722921191.708291782] [Move_demo_sub_node]: *******Movej_p succeeded //MoveJ_P运动成功时的提示信息 + [move_demo-1] + [move_demo-1] [INFO] [1722921193.977513811] [Move_demo_sub_node]: *******MoveL succeeded //MoveL运动成功时的提示信息 + [move_demo-1] + [move_demo-1] [INFO] [1722921194.075138936] [Move_demo_sub_node]: *******MoveC succeeded //MoveC运动成功时的提示信息 + ``` +## 6.关键代码说明 + +下面是 `api_Move_demo.cpp` 文件的主要功能: + +- **初始化** +相关发布订阅信息初始化 + + 声明movej_p发布器 + ``` + rclcpp::Publisher::SharedPtr movej_p_publisher_; + ``` + + 声明movel发布器 + ``` + rclcpp::Publisher::SharedPtr movel_publisher_; + ``` + + 声明movej发布器 + ``` + rclcpp::Publisher::SharedPtr movej_publisher_; + ``` + + 声明movec发布器 + ``` + rclcpp::Publisher::SharedPtr movec_publisher_; + ``` + + 声明movej_p订阅器 + ``` + rclcpp::Subscription::SharedPtr movej_p_subscription_; + ``` + + 声明movel订阅器 + ``` + rclcpp::Subscription::SharedPtr movel_subscription_; + ``` + + 声明movej订阅器 + ``` + rclcpp::Subscription::SharedPtr movej_subscription_; + ``` + + 声明movec订阅器 + ``` + rclcpp::Subscription::SharedPtr movec_subscription_; + ``` + +- **回调函数** +接收机械臂版本信息,进入消息回调函数 + + 构造函数 + ``` + MoveDemoSub(); + ``` + + movej_p结果回调函数 + ``` + void MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); + ``` + + movel结果回调函数 + ``` + void MoveJDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); + ``` + + movej结果回调函数 + ``` + void MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); + ``` + + movec结果回调函数 + ``` + void MoveCDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); + ``` + +- **发布MoveJ指令** +发布MoveJ指令使机械臂运动到目标位姿。 + + ```ROS + this->movej_publisher_->publish(movej_way); + ``` + +- **发布MoveJ_P指令** +发布MoveJ_P指令使机械臂运动到目标位姿。 + + ```ROS + this->movej_p_publisher_->publish(moveJ_P_TargetPose); + ``` + +- **发布MoveL指令** +发布MoveL指令使机械臂运动到目标位姿。 + + ```ROS + this->movel_publisher_->publish(moveL_TargetPose); + ``` + +- **发布MoveC指令** +发布MoveC指令使机械臂运动到目标位姿。 + + ```ROS + this->movec_publisher_->publish(moveC_TargetPose); + ``` + +## 7.许可证信息 + +* 具体许可证内容请参见`LICENSE`文件。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_65_move.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_65_move.launch.py new file mode 100755 index 0000000..df97600 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_65_move.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + move_node = Node( + package='control_arm_move', #节点所在的功能包 + executable='move_demo', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'arm_dof': 6} + ], #接入自由度参数 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(move_node) + return ld + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_75_move.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_75_move.launch.py new file mode 100755 index 0000000..a36878f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/launch/rm_75_move.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + move_node = Node( + package='control_arm_move', #节点所在的功能包 + executable='move_demo', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'arm_dof': 7} + ], #接入自由度参数 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(move_node) + return ld + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/package.xml new file mode 100755 index 0000000..00cc93e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/package.xml @@ -0,0 +1,21 @@ + + + + control_arm_move + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + rclcpp + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/src/api_Move_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/src/api_Move_demo.cpp new file mode 100755 index 0000000..b34de63 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/control_arm_move/src/api_Move_demo.cpp @@ -0,0 +1,260 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "rm_ros_interfaces/msg/movel.hpp" +#include "rm_ros_interfaces/msg/movej.hpp" +#include "rm_ros_interfaces/msg/movec.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; +bool movej_state = false; +bool movej_p_state = false; +bool movel_state = false; +bool movec_state = false; +bool first_run = true; +/****************************************创建类************************************/ +class MoveDemoPub: public rclcpp::Node +{ + public: + MoveDemoPub(); //构造函数 + void looppub_timer_callback(); //move运动规划函数 + + + + private: + rclcpp::Publisher::SharedPtr movej_p_publisher_; //声明发布器 + rclcpp::Publisher::SharedPtr movel_publisher_; //声明发布器 + rclcpp::Publisher::SharedPtr movej_publisher_; //声明发布器 + rclcpp::Publisher::SharedPtr movec_publisher_; + rclcpp::TimerBase::SharedPtr loop_pub_Timer; //定时发布器 + rm_ros_interfaces::msg::Movej movej_way; + int arm_dof_ = 6; +}; + +/****************************************创建类************************************/ +class MoveDemoSub: public rclcpp::Node +{ + public: + MoveDemoSub(); //构造函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void MoveJDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void MoveCDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + + + private: + rclcpp::Subscription::SharedPtr movej_p_subscription_; //声明订阅器 + rclcpp::Subscription::SharedPtr movel_subscription_; //声明订阅器 + rclcpp::Subscription::SharedPtr movej_subscription_; //声明订阅器 + rclcpp::Subscription::SharedPtr movec_subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveDemoSub::MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movej_p_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******Movej_p succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******Movej_p Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveDemoSub::MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movel_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveL succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******MoveL Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveDemoSub::MoveJDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movej_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******Movej succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******Movej Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveDemoSub::MoveCDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movec_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveC succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******MoveC Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************movejp运动函数****************************************/ +void MoveDemoPub::looppub_timer_callback() +{ + if(first_run == true) + { + + if(arm_dof_ == 6) + { + movej_way.joint[0] = -0.360829; + movej_way.joint[1] = 0.528468; + movej_way.joint[2] = 1.326293; + movej_way.joint[3] = -0.000454; + movej_way.joint[4] = 1.221748; + movej_way.joint[5] = 0.000052; + movej_way.speed = 20; + movej_way.dof = 6; + } + if(arm_dof_ == 7) + { + movej_way.joint[0] = 0.176278; + movej_way.joint[1] = 0.0; + movej_way.joint[2] = 0.3543; + movej_way.joint[3] = 0.53; + movej_way.joint[4] = 0.00873; + movej_way.joint[5] = 0.3595; + movej_way.joint[6] = 0.3595; + movej_way.speed = 20; + movej_way.dof = 7; + } + movej_way.block = true; + this->movej_publisher_->publish(movej_way); + first_run = false; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + + } + if(movej_state == true) + { + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + moveJ_P_TargetPose.pose.position.x = -0.355816; + moveJ_P_TargetPose.pose.position.y = -0.000013; + moveJ_P_TargetPose.pose.position.z = 0.222814; + moveJ_P_TargetPose.pose.orientation.x = 0.995179; + moveJ_P_TargetPose.pose.orientation.y = -0.094604; + moveJ_P_TargetPose.pose.orientation.z = -0.025721; + moveJ_P_TargetPose.pose.orientation.w = 0.002349; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.block = true; + this->movej_p_publisher_->publish(moveJ_P_TargetPose); + movej_state = false; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + } + + if(movej_p_state == true) + { + rm_ros_interfaces::msg::Movel moveL_TargetPose; + moveL_TargetPose.pose.position.x = -0.255816; + moveL_TargetPose.pose.position.y = -0.000013; + moveL_TargetPose.pose.position.z = 0.222814; + moveL_TargetPose.pose.orientation.x = 0.995179; + moveL_TargetPose.pose.orientation.y = -0.094604; + moveL_TargetPose.pose.orientation.z = -0.025721; + moveL_TargetPose.pose.orientation.w = 0.002349; + moveL_TargetPose.speed = 20; + moveL_TargetPose.block = true; + this->movel_publisher_->publish(moveL_TargetPose); + movej_p_state = false; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + } + + if(movel_state == true) + { + rm_ros_interfaces::msg::Movec moveC_TargetPose; + moveC_TargetPose.pose_mid.position.x = -0.307239; + moveC_TargetPose.pose_mid.position.y = 0.150903; + moveC_TargetPose.pose_mid.position.z = 0.222814; + moveC_TargetPose.pose_mid.orientation.x = 0.995179; + moveC_TargetPose.pose_mid.orientation.y = -0.094604; + moveC_TargetPose.pose_mid.orientation.z = -0.025721; + moveC_TargetPose.pose_mid.orientation.w = 0.002349; + moveC_TargetPose.pose_end.position.x = -0.357239; + moveC_TargetPose.pose_end.position.y = 0.000903; + moveC_TargetPose.pose_end.position.z = 0.222814; + moveC_TargetPose.pose_end.orientation.x = 0.995179; + moveC_TargetPose.pose_end.orientation.y = -0.094604; + moveC_TargetPose.pose_end.orientation.z = -0.025721; + moveC_TargetPose.pose_end.orientation.w = 0.002349; + moveC_TargetPose.speed = 20; + moveC_TargetPose.loop = 1; + moveC_TargetPose.trajectory_connect = 0; + moveC_TargetPose.block = true; + this->movec_publisher_->publish(moveC_TargetPose); + movel_state = false; + } + +} +/***********************************************end**************************************************/ + + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveDemoPub::MoveDemoPub():rclcpp::Node("Move_demo_pub_node") +{ + this->declare_parameter("arm_dof", arm_dof_); + this->get_parameter("arm_dof", arm_dof_); + RCLCPP_INFO (this->get_logger(),"arm_dof is %d\n",arm_dof_); + if(arm_dof_ == 6) + {movej_way.joint.resize(6);} + else if(arm_dof_ == 7) + {movej_way.joint.resize(7);} + movej_p_publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + movel_publisher_ = this->create_publisher("/rm_driver/movel_cmd", rclcpp::ParametersQoS()); + movej_publisher_ = this->create_publisher("/rm_driver/movej_cmd", rclcpp::ParametersQoS()); + movec_publisher_ = this->create_publisher("/rm_driver/movec_cmd", rclcpp::ParametersQoS()); + loop_pub_Timer = this->create_wall_timer(std::chrono::milliseconds(100), + std::bind(&MoveDemoPub::looppub_timer_callback,this)); + std::this_thread::sleep_for(std::chrono::milliseconds(3000)); + +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveDemoSub::MoveDemoSub():rclcpp::Node("Move_demo_sub_node") +{ + movej_p_subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&MoveDemoSub::MoveJPDemo_Callback, this,_1)); + movel_subscription_ = this->create_subscription("/rm_driver/movel_result", rclcpp::ParametersQoS(), std::bind(&MoveDemoSub::MoveLDemo_Callback, this,_1)); + movej_subscription_ = this->create_subscription("/rm_driver/movej_result", rclcpp::ParametersQoS(), std::bind(&MoveDemoSub::MoveJDemo_Callback, this,_1)); + movec_subscription_ = this->create_subscription("/rm_driver/movec_result", rclcpp::ParametersQoS(), std::bind(&MoveDemoSub::MoveCDemo_Callback, this,_1)); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node_sub = std::make_shared(); + auto node_pub = std::make_shared(); + executor.add_node(node_pub); + executor.add_node(node_sub); + executor.spin(); + rclcpp::shutdown(); + return 0; +} + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/CMakeLists.txt new file mode 100755 index 0000000..97716a1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/CMakeLists.txt @@ -0,0 +1,47 @@ +cmake_minimum_required(VERSION 3.8) +project(force_position_control) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) + + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + + set(ament_cmake_copyright_FOUND TRUE) + + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +add_executable(rm_force_position_control src/api_Force_Position_Control_demo.cpp) + +ament_target_dependencies(rm_force_position_control rclcpp std_msgs rm_ros_interfaces) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME}) + +install(TARGETS +rm_force_position_control + DESTINATION lib/${PROJECT_NAME}) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/LICENSE b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/LICENSE new file mode 100644 index 0000000..473abff --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/LICENSE @@ -0,0 +1,13 @@ +Copyright 2024 realman-robotics + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/README.md new file mode 100644 index 0000000..1b531a7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/README.md @@ -0,0 +1,169 @@ +# 力位混合控制规划`ARM_FORCE_POSITION_CONTROL_DEMO` + +--- + +## **1.项目介绍** + +本项目是一个基于RM65、RM75机械臂和ROS功能包实现力位混合控制规划运动功能(该功能适用于类似于MoveL的笛卡尔运动,不适用与MoveJ等关节运动),程序在执行时会依次执行开启力位混合控制,进行笛卡尔运动,关闭力位混合控制的操作,目的是使ROS开发者迅速掌握并灵活运用机械臂。 + +## **2. 代码结构** + +``` +├── CMakeLists.txt <-CMake编译文件 +├── launch <-启动文件夹 +│   └── force_position_control_demo.launch <-启动文件 +├── LICENSE <-版本说明 +├── package.xml <-依赖描述文件夹 +├── README.md <-说明文档 +└── src <-C++源码文件夹 + └── api_force_position_control_demo.cpp <-源码文件 +``` +## **3.项目下载** + +通过项目链接下载本项目工程文件到本地:[ros2_rm_robot](https://github.com/RealManRobot/ros2_rm_robot/tree/humble) + +## **4.环境配置** + +| 项目 | 内容 | +| :-- | :-- | +| 系统 | Ubuntu22.04 | +| ROS版本 | humble | +| 依赖 | 机械臂的ROS2-humble功能包 | + +**配置过程** + +1. 首先需要准备好Ubuntu22.04操作系统的虚拟机或其他设备。 +2. 安装ROS2环境[humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html),也可参考ROS2-humble功能包中的安装说明进行安装。 +3. ROS2-Humble功能包安装 + + 新建工作空间和src文件 + ``` + mkdir -p ~/ros2_ws/src + ``` + + 将ROS2文件放入src中 + ``` + cp -r ros2_rm_robot ~/ros2_ws/src + ``` + + 进入工作空间 + ``` + cd ~/ros2_ws + ``` + + 编译rm_ros_interfaces功能包 + ``` + colcon build --packages-select rm_ros_interfaces + ``` + 声明环境变量 + ``` + source ./install/setup.bash + ``` + + 编译所有功能包 + ``` + colcon build + ``` + + 再次声明环境变量 + ``` + source ./install/setup.bash + +## **5. 使用指南** + +* **命令行使用**: + + 我们需要在一个终端中启动机械臂的rm_driver功能包。 + ``` + ros2 launch rm_driver rm__driver.launch.py + ``` + 可以为65、63、eco65、75、gen72,可对照自己使用的设备进行实际选择 + 我们需要在另一个终端中启动机械臂的force_position_control功能包。 + ``` + ros2 launch force_position_control force_position_control_demo.launch.py + ``` + 若非RM65、RM75机械臂可能会出现无法到达点位的情况,为正常现象。 +* **返回信息**: + + 在程序成功运行时将会出现以下提示信息。 + ``` +[rm_force_position_control-1] [INFO] [1722914114.076652595] [Force_Position_Control_sub_node]: *******Movej_p succeeded //Movej_p运动成功提示 +[rm_force_position_control-1] +[rm_force_position_control-1] [INFO] [1722914114.248853737] [Force_Position_Control_sub_node]: *******Set Force Postion succeeded //力位混合控制设置成功提示 +[rm_force_position_control-1] +[rm_force_position_control-1] [INFO] [1722914116.432832020] [Force_Position_Control_sub_node]: *******MoveL succeeded //Movel运动成功提示 +[rm_force_position_control-1] +[rm_force_position_control-1] [INFO] [1722914116.548136946] [Force_Position_Control_sub_node]: *******Stop Force Postion succeeded //结束力位混合控制设置成功提示 +[rm_force_position_control-1] +[rm_force_position_control-1] [INFO] [1722914116.647943527] [Force_Position_Control_pub_node]: *******All step run over //指令运行完成提示 + ``` + +* **关键代码说明**: + +下面是 `api_force_position_control_demo.cpp` 文件的主要功能: + +- **初始化** +相关发布订阅信息初始化 + + ```ROS + rclcpp::Subscription::SharedPtr movej_p_subscription_; //声明movej_p运动订阅器 + rclcpp::Subscription::SharedPtr movel_subscription_; //声明movel运动订阅器 + + rclcpp::Subscription::SharedPtr set_force_postion_subscription_; //声明力位混合控制订阅器 + rclcpp::Subscription::SharedPtr stop_force_postion_subscription_; //声明停止力位混合控制订阅器 + rclcpp::Publisher::SharedPtr movej_p_publisher_; //声明Movej_p运动发布器 + rclcpp::Publisher::SharedPtr movel_publisher_; //声明Movel运动发布器 + + rclcpp::Publisher::SharedPtr set_force_postion_publisher_; //声明力位混合控制发布器 + rclcpp::Publisher::SharedPtr stop_force_postion_publisher_; //声明停止力位混合控制发布器 + ``` + +- **回调函数** +接收到订阅的机械臂执行状态消息后,会进入消息回调函数 + + void MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //Movej_p运动结果回调函数 + void SetForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //力位混合控制结果回调函数 + void MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //Movel运动结果回调函数 + void StopForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //停止力位混合控制结果回调函数 + +- **发布MoveJ_P指令** +发布MoveJ_P指令使机械臂运动到目标位姿。 + + ```ROS + this->movej_p_publisher_->publish(moveJ_P_TargetPose); + ``` + +- **发布开启力位混合指令** +设置机械臂开启力位混合指令。 + + ```ROS + this->set_force_postion_publisher_->publish(forceposition_data); + ``` + +- **发布MoveL指令** +发布MoveL指令使机械臂运动到目标位姿。 + + ```ROS + this->movel_publisher_->publish(moveL_TargetPose); + ``` + +- **发布关闭力位混合指令** +发布MoveL指令使机械臂运动到目标位姿。 + + ```ROS + this->stop_force_postion_publisher_->publish(stop_force_postion_data); + ``` + +## **6. 许可证信息** + +* 具体许可证内容请参见`LICENSE`文件。 + +## **7. 常见问题解答(FAQ)** + +- **Q1:机械臂连接失败** + + 答案:修改过机械臂IP + +- **Q2:UDP数据推送接口收不到数据** + + 答案:检查线程模式、是否使能推送数据、IP以及防火墙 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/launch/force_position_control_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/launch/force_position_control_demo.launch.py new file mode 100755 index 0000000..bee009c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/launch/force_position_control_demo.launch.py @@ -0,0 +1,12 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + force_position_control_node = Node( + package='force_position_control', #节点所在的功能包 + executable='rm_force_position_control', #表示要运行的可执行文件名或脚本名字.py + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(force_position_control_node) + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/package.xml new file mode 100755 index 0000000..c52060b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/package.xml @@ -0,0 +1,21 @@ + + + + force_position_control + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + rclcpp + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/src/api_Force_Position_Control_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/src/api_Force_Position_Control_demo.cpp new file mode 100644 index 0000000..0197ee7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/force_position_control/src/api_Force_Position_Control_demo.cpp @@ -0,0 +1,222 @@ +// +// Created by ubuntu on 24-7-11. +// +#include +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "rm_ros_interfaces/msg/movel.hpp" +#include "rm_ros_interfaces/msg/setforceposition.hpp" +#include "rm_ros_interfaces/msg/movec.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; +bool set_force_postion_state = false; +bool movej_p_state = false; +bool movel_state = false; +bool stop_force_postion_state = false; +bool first_run = true; +/****************************************创建类************************************/ +class ForcePositionControlDemoSub: public rclcpp::Node +{ + public: + ForcePositionControlDemoSub(); //构造函数 + void ForcePositionControl_demo(); //力位混合运动规划函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void SetForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + void StopForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg); //结果回调函数 + + private: + rclcpp::Subscription::SharedPtr movej_p_subscription_; //声明订阅器 + rclcpp::Subscription::SharedPtr movel_subscription_; //声明订阅器 + + rclcpp::Subscription::SharedPtr set_force_postion_subscription_; //声明订阅器 + rclcpp::Subscription::SharedPtr stop_force_postion_subscription_; //声明订阅器 + +}; + +class ForcePositionControlDemoPub: public rclcpp::Node +{ + public: + ForcePositionControlDemoPub(); //构造函数 + void ForcePositionControl_demo(); //力位混合运动规划函数 + void looppub_timer_callback(); //move运动规划函数 + + private: + rclcpp::Publisher::SharedPtr movej_p_publisher_; //声明发布器 + rclcpp::Publisher::SharedPtr movel_publisher_; //声明发布器 + + rclcpp::Publisher::SharedPtr set_force_postion_publisher_;//声明发布器 + rclcpp::Publisher::SharedPtr stop_force_postion_publisher_; //声明发布器 + rclcpp::TimerBase::SharedPtr loop_pub_Timer; //定时发布器 + +}; + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void ForcePositionControlDemoSub::MoveJPDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movej_p_state = true; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******Movej_p succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******Movej_p Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void ForcePositionControlDemoSub::MoveLDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + movel_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveL succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******MoveL Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void ForcePositionControlDemoSub::SetForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + set_force_postion_state = msg->data; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******Set Force Postion succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******Set Force Postion Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void ForcePositionControlDemoSub::StopForcePostionDemo_Callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + stop_force_postion_state = true; + if(msg->data) + { + RCLCPP_INFO (this->get_logger(),"*******Stop Force Postion succeeded\n"); + } else { + RCLCPP_ERROR (this->get_logger(),"*******Stop Force Postion Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************力位混合运动函数****************************************/ +void ForcePositionControlDemoPub::looppub_timer_callback() +{ + //moveJP到达指定位置 + if(first_run ==true) + { + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + moveJ_P_TargetPose.pose.position.x = -0.355816; + moveJ_P_TargetPose.pose.position.y = -0.000013; + moveJ_P_TargetPose.pose.position.z = 0.222814; + moveJ_P_TargetPose.pose.orientation.x = 0.995179; + moveJ_P_TargetPose.pose.orientation.y = -0.094604; + moveJ_P_TargetPose.pose.orientation.z = -0.025721; + moveJ_P_TargetPose.pose.orientation.w = 0.002349; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.block = true; + this->movej_p_publisher_->publish(moveJ_P_TargetPose); + first_run = false; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + } + //开启力位混合 + if(movej_p_state==true) //等待moveJ_P到达 + { + rm_ros_interfaces::msg::Setforceposition forceposition_data; + forceposition_data.sensor = 1; + forceposition_data.mode = 0; + forceposition_data.direction = 2; + forceposition_data.n = 5; + // forceposition_data.block = true; + this->set_force_postion_publisher_->publish(forceposition_data); + movej_p_state = false; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + //moveL运动 + if(set_force_postion_state==true) + { + rm_ros_interfaces::msg::Movel moveL_TargetPose; + moveL_TargetPose.pose.position.x = -0.255816; + moveL_TargetPose.pose.position.y = -0.000013; + moveL_TargetPose.pose.position.z = 0.222814; + moveL_TargetPose.pose.orientation.x = 0.995179; + moveL_TargetPose.pose.orientation.y = -0.094604; + moveL_TargetPose.pose.orientation.z = -0.025721; + moveL_TargetPose.pose.orientation.w = 0.002349; + moveL_TargetPose.speed = 20; + moveL_TargetPose.block = true; + this->movel_publisher_->publish(moveL_TargetPose); + set_force_postion_state = false; + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + } + //停止力位混合 + if(movel_state==true) //等待movel到达 + { + std_msgs::msg::Bool stop_force_postion_data; + stop_force_postion_data.data = true; + this->stop_force_postion_publisher_->publish(stop_force_postion_data); + movel_state = false; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + if(stop_force_postion_state==true) + { + RCLCPP_INFO (this->get_logger(),"*******All step run over\n"); + stop_force_postion_state = false; + } +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +ForcePositionControlDemoPub::ForcePositionControlDemoPub():rclcpp::Node("Force_Position_Control_pub_node") +{ + movej_p_publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + movel_publisher_ = this->create_publisher("/rm_driver/movel_cmd", rclcpp::ParametersQoS()); + set_force_postion_publisher_ = this->create_publisher("/rm_driver/set_force_postion_cmd", rclcpp::ParametersQoS()); + stop_force_postion_publisher_ = this->create_publisher("/rm_driver/stop_force_postion_cmd", rclcpp::ParametersQoS()); + loop_pub_Timer = this->create_wall_timer(std::chrono::milliseconds(100), + std::bind(&ForcePositionControlDemoPub::looppub_timer_callback,this)); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +ForcePositionControlDemoSub::ForcePositionControlDemoSub():rclcpp::Node("Force_Position_Control_sub_node") +{ + movej_p_subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&ForcePositionControlDemoSub::MoveJPDemo_Callback, this,_1)); + movel_subscription_ = this->create_subscription("/rm_driver/movel_result", rclcpp::ParametersQoS(), std::bind(&ForcePositionControlDemoSub::MoveLDemo_Callback, this,_1)); + set_force_postion_subscription_ = this->create_subscription("/rm_driver/set_force_postion_result", rclcpp::ParametersQoS(), std::bind(&ForcePositionControlDemoSub::SetForcePostionDemo_Callback, this,_1)); + stop_force_postion_subscription_ = this->create_subscription("/rm_driver/stop_force_postion_result", rclcpp::ParametersQoS(), std::bind(&ForcePositionControlDemoSub::StopForcePostionDemo_Callback, this,_1)); + std::this_thread::sleep_for(std::chrono::milliseconds(3000)); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node_sub = std::make_shared(); + auto node_pub = std::make_shared(); + executor.add_node(node_pub); + executor.add_node(node_sub); + + executor.spin(); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/CMakeLists.txt new file mode 100755 index 0000000..ca4476c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/CMakeLists.txt @@ -0,0 +1,44 @@ +cmake_minimum_required(VERSION 3.8) +project(get_arm_state) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + set(ament_cmake_copyright_FOUND TRUE) + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +add_executable(rm_get_arm_state_demo src/api_Get_Arm_State_demo.cpp) + +ament_target_dependencies(rm_get_arm_state_demo rclcpp std_msgs rm_ros_interfaces) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME}) + +install(TARGETS +rm_get_arm_state_demo + DESTINATION lib/${PROJECT_NAME}) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/LICENSE b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/LICENSE new file mode 100644 index 0000000..473abff --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/LICENSE @@ -0,0 +1,13 @@ +Copyright 2024 realman-robotics + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/README.md new file mode 100644 index 0000000..4139f01 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/README.md @@ -0,0 +1,244 @@ +# 获取机械臂状态`GET_ARM_STATE_DEMO` + +--- + +## 1.项目介绍 + +本项目是一个基于机械臂机械臂本体和ROS功能包实现获取机械臂当前控制器版本、关节状态、位姿状态、六维力信息功能,程序将依次执行获取控制器版本信息,获取机械臂状态,获取六维力数据信息的指令,程序执行时,对应的数据信息会打印在终端中,该示例目的是使ROS开发者迅速掌握并灵活运用机械臂。 + +## 2. 代码结构 + +``` +├── CMakeLists.txt <-CMake编译文件 +├── launch <-启动文件夹 +│   └── get_arm_state_demo.launch.py <-启动文件 +├── LICENSE <-版本说明 +├── package.xml <-依赖描述文件夹 +├── README.md <-说明文档 +└── src <-C++源码文件夹 + └── api_Get_Arm_State_demo.cpp <-源码文件 +``` + +## 3.项目下载 + +通过项目链接下载本项目工程文件到本地:[ros2_rm_robot](https://github.com/RealManRobot/ros2_rm_robot/tree/humble) + +## 4.环境配置 + +| 项目 | 内容 | +| :-- | :-- | +| 系统 | Ubuntu22.04 | +| ROS版本 | humble | +| 依赖 | 机械臂的ROS2-humble功能包 | + +1. 首先需要准备好Ubuntu22.04操作系统的虚拟机或其他设备。 +2. 安装ROS2环境[humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html),也可参考ROS2-humble功能包中的安装说明进行安装。 +3. ROS2-Humble功能包安装 + + 新建工作空间和src文件夹 + ``` + mkdir -p ~/ros2_ws/src + ``` + + 将ROS2文件复制到src文件夹中 + ``` + cp -r ros2_rm_robot ~/ros2_ws/src + ``` + + 进入工作空间 + ``` + cd ~/ros2_ws + ``` + + 编译rm_ros_interfaces功能包 + ``` + colcon build --packages-select rm_ros_interfaces + ``` + + 声明环境变量 + ``` + source ./install/setup.bash + ``` + + 编译所有功能包 + ``` + colcon build + ``` + + 再次声明环境变量 + ``` + source ./install/setup.bash + ``` + +## 5. 使用指南 + +* **命令行使用**: + + 我们需要在一个终端中启动机械臂的rm_driver功能包。 + ``` + ros2 launch rm_driver rm__driver.launch.py + ``` + 可以为65、63、eco65、75、gen72,可对照自己使用的设备进行实际选择 + 我们需要在另一个终端中启动机械臂的get_arm_state功能包。 + ``` + ros2 launch get_arm_state get_arm_state_demo.launch.py + ``` +* **返回信息**: + + 在程序成功运行时将会出现以下提示信息。 + ``` + [rm_get_arm_state_demo-1] [INFO] [1722912567.024745517] [get_state]: joint state is: [0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000] //机械臂角度信息 + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1722912567.024994866] [get_state]: pose state is: [0.000000, 0.000000, 0.534000, 3.141000, 0.000000, 0.000000] //机械臂位姿信息(欧拉角) + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1722912567.025200125] [get_state]: joint state is: [0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000] //机械臂弧度信息 + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1722912567.025321800] [get_state]: pose state is: //机械臂位姿信息(四元数) + [rm_get_arm_state_demo-1] [position.x = 0.000000, + [rm_get_arm_state_demo-1] position.y = 0.000000, + [rm_get_arm_state_demo-1] position.z = 0.534000, + [rm_get_arm_state_demo-1] orientation.x = 1.000000, + [rm_get_arm_state_demo-1] orientation.y = 0.000000, + [rm_get_arm_state_demo-1] orientation.z = 0.000000, + [rm_get_arm_state_demo-1] orientation.w = 0.000296] + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1722912567.025408782] [get_state]: Planversion is 7B0156 //机械臂控制器版本信息(7代表自由度,b代表没有六维力,156为控制器程序版本为1.5.6) + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1722912567.025463071] [get_state]: Productversion is GEN72-BI //机械臂设备型号息信息 + [rm_get_arm_state_demo-1] [INFO] [1723550015.625603508] [get_state]: + [rm_get_arm_state_demo-1] [INFO] [1723550325.782782033] [get_state]: // 六维力传感器原始数据 + [rm_get_arm_state_demo-1] force-force_fx is 0.000000 + [rm_get_arm_state_demo-1] force-force_fy is 0.000000 + [rm_get_arm_state_demo-1] force-force_fz is 0.000000 + [rm_get_arm_state_demo-1] force-force_mx is 0.000000 + [rm_get_arm_state_demo-1] force-force_my is 0.000000 + [rm_get_arm_state_demo-1] force-force_mz is 0.000000 + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1723550325.782929425] [get_state]: // 六维力传感器系统受力数据 + [rm_get_arm_state_demo-1] zero-force_fx is 0.000000 + [rm_get_arm_state_demo-1] zero-force_fy is 0.000000 + [rm_get_arm_state_demo-1] zero-force_fz is 0.000000 + [rm_get_arm_state_demo-1] zero-force_mx is 0.000000 + [rm_get_arm_state_demo-1] zero-force_my is 0.000000 + [rm_get_arm_state_demo-1] zero-force_mz is 0.000000 + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1723550325.782964040] [get_state]: // 六维力传感器工作坐标系受力数据 + [rm_get_arm_state_demo-1] work-zero_fx is 0.000000 + [rm_get_arm_state_demo-1] work-zero_fy is 0.000000 + [rm_get_arm_state_demo-1] work-zero_fz is 0.000000 + [rm_get_arm_state_demo-1] work-zero_mx is 0.000000 + [rm_get_arm_state_demo-1] work-zero_my is 0.000000 + [rm_get_arm_state_demo-1] work-zero_mz is 0.000000 + [rm_get_arm_state_demo-1] + [rm_get_arm_state_demo-1] [INFO] [1723550325.782985859] [get_state]: // 六维力传感器工具坐标系受力数据 + [rm_get_arm_state_demo-1] tool-zero_fx is 0.000000 + [rm_get_arm_state_demo-1] tool-zero_fy is 0.000000 + [rm_get_arm_state_demo-1] tool-zero_fz is 0.000000 + [rm_get_arm_state_demo-1] tool-zero_mx is 0.000000 + [rm_get_arm_state_demo-1] tool-zero_my is 0.000000 + [rm_get_arm_state_demo-1] tool-zero_mz is 0.000000 + ``` + +## 6.关键代码说明 + +下面是 `api_Get_Arm_State_demo.cpp` 文件的主要功能: + +- **初始化** +相关发布订阅信息初始化 + + 机械臂关节状态发布器 + ``` + rclcpp::Publisher::SharedPtr arm_state_publisher_; + ``` + + 机械臂软件版本发布器 + ``` + rclcpp::Publisher::SharedPtr arm_software_version_publisher_; + ``` + + 机械臂六维力状态发布器 + ``` + rclcpp::Publisher::SharedPtr get_force_data_publisher_; + ``` + + 关节原始状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_original_state; + ``` + + 关节状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_arm_state; + ``` + + 控制器版本订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_software_version; + ``` + + 六维力传感器状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_force_data; + ``` + + 六维力系统受力状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_zero_force_data; + ``` + + 六维力工作坐标系受力状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_work_force_data; + ``` + + 六维力工具坐标系受力状态订阅器 + ``` + rclcpp::Subscription::SharedPtr subscription_tool_force_data; + ``` + +- **回调函数** +接收机械臂版本信息,进入消息回调函数 + + 改变工作坐标系函数 + ``` + void get_arm_state(); + ``` + + 机械臂状态原始结果回调函数 + ``` + void GetArmOriginalState_Callback(const rm_ros_interfaces::msg::Armoriginalstate::SharedPtr msg); + ``` + + 机械臂状态结果回调函数 + ``` + void GetArmState_Callback(const rm_ros_interfaces::msg::Armstate::SharedPtr msg); + ``` + + 控制器版本结果回调函数 + ``` + void GetArmSoftwareVersion_Callback(const rm_ros_interfaces::msg::Armsoftversion::SharedPtr msg); + ``` + + 六维力传感器结果回调函数 + ``` + void ForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); + ``` + + 六维力结果回调函数 + ``` + void ZeroForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); + ``` + + 六维力工作坐标结果回调函数 + ``` + void WorkForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); + ``` + + 六维力工具坐标结果回调函数 + ``` + void ToolForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); + ``` + +## 7.许可证信息 + +* 具体许可证内容请参见`LICENSE`文件。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/launch/get_arm_state_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/launch/get_arm_state_demo.launch.py new file mode 100755 index 0000000..61bf247 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/launch/get_arm_state_demo.launch.py @@ -0,0 +1,14 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + get_arm_state_node = Node( + package='get_arm_state', #节点所在的功能包 + executable='rm_get_arm_state_demo', #表示要运行的可执行文件名或脚本名字.py + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(get_arm_state_node) + return ld + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/package.xml new file mode 100755 index 0000000..6d1503e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/package.xml @@ -0,0 +1,21 @@ + + + + get_arm_state + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + rclcpp + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/src/api_Get_Arm_State_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/src/api_Get_Arm_State_demo.cpp new file mode 100755 index 0000000..e19c298 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_arm_examples/get_arm_state/src/api_Get_Arm_State_demo.cpp @@ -0,0 +1,172 @@ +// +// Created by ubuntu on 24-7-10. +// +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/armoriginalstate.hpp" +#include "rm_ros_interfaces/msg/armstate.hpp" +#include "rm_ros_interfaces/msg/armsoftversion.hpp" +#include "rm_ros_interfaces/msg/sixforce.hpp" +#include "std_msgs/msg/empty.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class GetArmState: public rclcpp::Node +{ + public: + GetArmState(); //构造函数 + void get_arm_state(); //改变工作坐标系函数 + void GetArmOriginalState_Callback(const rm_ros_interfaces::msg::Armoriginalstate::SharedPtr msg); //机械臂状态原始结果回调函数 + void GetArmState_Callback(const rm_ros_interfaces::msg::Armstate::SharedPtr msg); //机械臂状态结果回调函数 + void GetArmSoftwareVersion_Callback(const rm_ros_interfaces::msg::Armsoftversion::SharedPtr msg); //控制器版本结果回调函数 + void ForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); //六维力传感器结果回调函数 + void ZeroForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); //六维力结果回调函数 + void WorkForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); //六维力工作坐标结果回调函数 + void ToolForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg); //六维力工具坐标结果回调函数 + + + private: + rclcpp::Publisher::SharedPtr arm_state_publisher_; //机械臂关节状态发布器 + rclcpp::Publisher::SharedPtr arm_software_version_publisher_; //机械臂软件版本发布器 + rclcpp::Publisher::SharedPtr get_force_data_publisher_; //机械臂六维力状态发布器 + rclcpp::Subscription::SharedPtr subscription_original_state; //关节原始状态订阅器 + rclcpp::Subscription::SharedPtr subscription_arm_state; //关节状态订阅器 + rclcpp::Subscription::SharedPtr subscription_software_version; //控制器版本订阅器 + rclcpp::Subscription::SharedPtr subscription_force_data; //六维力传感器状态订阅器 + rclcpp::Subscription::SharedPtr subscription_zero_force_data; //六维力系统受力状态订阅器 + rclcpp::Subscription::SharedPtr subscription_work_force_data; //六维力工作坐标系受力状态订阅器 + rclcpp::Subscription::SharedPtr subscription_tool_force_data; //六维力工具坐标系受力状态订阅器 +}; + + +/************************************************机械臂状态原始结果回调********************************************/ +void GetArmState::GetArmOriginalState_Callback(const rm_ros_interfaces::msg::Armoriginalstate::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg->dof == 7) + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf, %lf]\n", msg->joint[0],msg->joint[1],msg->joint[2],msg->joint[3],msg->joint[4],msg->joint[5],msg->joint[6]); + } + else + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf]\n", msg->joint[0],msg->joint[1],msg->joint[2],msg->joint[3],msg->joint[4],msg->joint[5]); + } + RCLCPP_INFO (this->get_logger(),"pose state is: [%lf, %lf, %lf, %lf, %lf, %lf]\n", msg->pose[0],msg->pose[1],msg->pose[2],msg->pose[3],msg->pose[4],msg->pose[5]); +} +/*******************************************************end**********************************************************/ + +/******************************************************机械臂状态结果回调***********************************************/ +void GetArmState::GetArmState_Callback(const rm_ros_interfaces::msg::Armstate::SharedPtr msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg->dof == 7) + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf, %lf]\n", msg->joint[0],msg->joint[1],msg->joint[2],msg->joint[3],msg->joint[4],msg->joint[5],msg->joint[6]); + } + else + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf]\n", msg->joint[0],msg->joint[1],msg->joint[2],msg->joint[3],msg->joint[4],msg->joint[5]); + } + RCLCPP_INFO (this->get_logger(),"pose state is: \n[position.x = %lf,\n position.y = %lf,\n position.z = %lf,\n orientation.x = %lf,\n orientation.y = %lf,\n orientation.z = %lf,\n orientation.w = %lf]\n", msg->pose.position.x,msg->pose.position.y,msg->pose.position.z,msg->pose.orientation.x,msg->pose.orientation.y,msg->pose.orientation.z,msg->pose.orientation.w); +} +/*******************************************************end**********************************************************/ +/************************************************机械臂传感器版本结果回调函数********************************************/ +void GetArmState::GetArmSoftwareVersion_Callback(const rm_ros_interfaces::msg::Armsoftversion::SharedPtr msg) +{ + RCLCPP_INFO(this->get_logger(),"Planversion is %s\n ", msg->planversion.c_str()); + RCLCPP_INFO(this->get_logger(),"Productversion is %s\n ", msg->productversion.c_str()); +} +/*******************************************************end**********************************************************/ +/************************************************机械臂传感器六维力结果回调函数********************************************/ +void GetArmState::ForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg) +{ + RCLCPP_INFO(this->get_logger(),"\nforce-force_fx is %f\nforce-force_fy is %f\nforce-force_fz is %f\nforce-force_mx is %f\nforce-force_my is %f\nforce-force_mz is %f\n " + , msg->force_fx + , msg->force_fy + , msg->force_fz + , msg->force_mx + , msg->force_my + , msg->force_mz); +} +/*******************************************************end**********************************************************/ +/***********************************************机械臂六维力系统受力结果回调函数******************************************/ +void GetArmState::ZeroForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg) +{ + RCLCPP_INFO(this->get_logger(),"\nzero-force_fx is %f\nzero-force_fy is %f\nzero-force_fz is %f\nzero-force_mx is %f\nzero-force_my is %f\nzero-force_mz is %f\n" + , msg->force_fx + , msg->force_fy + , msg->force_fz + , msg->force_mx + , msg->force_my + , msg->force_mz); +} +/*******************************************************end**********************************************************/ +/***********************************************机械臂六维力系统受力结果回调函数******************************************/ +void GetArmState::WorkForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg) +{ + RCLCPP_INFO(this->get_logger(),"\nwork-zero_fx is %f\nwork-zero_fy is %f\nwork-zero_fz is %f\nwork-zero_mx is %f\nwork-zero_my is %f\nwork-zero_mz is %f\n " + , msg->force_fx + , msg->force_fy + , msg->force_fz + , msg->force_mx + , msg->force_my + , msg->force_mz); +} +/*******************************************************end**********************************************************/ +/***********************************************机械臂六维力系统受力结果回调函数******************************************/ +void GetArmState::ToolForceData_Callback(const rm_ros_interfaces::msg::Sixforce::SharedPtr msg) +{ + RCLCPP_INFO(this->get_logger(),"\ntool-zero_fx is %f\ntool-zero_fy is %f\ntool-zero_fz is %f\ntool-zero_mx is %f\ntool-zero_my is %f\ntool-zero_mz is %f\n" + , msg->force_fx + , msg->force_fy + , msg->force_fz + , msg->force_mx + , msg->force_my + , msg->force_mz); +} +/*******************************************************end**********************************************************/ + +/*******************************************获取位姿函数****************************************/ +void GetArmState::get_arm_state() +{ + std_msgs::msg::Empty get_state; + std::this_thread::sleep_for(std::chrono::milliseconds(3000)); + this->arm_state_publisher_->publish(get_state); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + this->arm_software_version_publisher_->publish(get_state); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + this->get_force_data_publisher_->publish(get_state); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +GetArmState::GetArmState():rclcpp::Node("get_state") +{ + subscription_original_state = this->create_subscription("/rm_driver/get_current_arm_original_state_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::GetArmOriginalState_Callback, this,_1)); + subscription_arm_state = this->create_subscription("/rm_driver/get_current_arm_state_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::GetArmState_Callback, this,_1)); + subscription_software_version = this->create_subscription("/rm_driver/get_arm_software_version_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::GetArmSoftwareVersion_Callback, this,_1)); + subscription_force_data = this->create_subscription("/rm_driver/get_force_data_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::ForceData_Callback, this,_1)); + subscription_zero_force_data = this->create_subscription("/rm_driver/get_zero_force_data_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::ZeroForceData_Callback, this,_1)); + subscription_work_force_data = this->create_subscription("/rm_driver/get_work_force_data_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::WorkForceData_Callback, this,_1)); + subscription_tool_force_data = this->create_subscription("/rm_driver/get_tool_force_data_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::ToolForceData_Callback, this,_1)); + arm_state_publisher_ = this->create_publisher("/rm_driver/get_current_arm_state_cmd", rclcpp::ParametersQoS()); + arm_software_version_publisher_ = this->create_publisher("/rm_driver/get_arm_software_version_cmd", rclcpp::ParametersQoS()); + get_force_data_publisher_ = this->create_publisher("/rm_driver/get_force_data_cmd", rclcpp::ParametersQoS()); + get_arm_state(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/CMakeLists.txt new file mode 100644 index 0000000..ba0f3ce --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_bringup) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README.md new file mode 100644 index 0000000..b2f6928 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README.md @@ -0,0 +1,136 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_bringup/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_bringup/README.md) + +
+ +
+ +# RealMan Robot rm_bringup User Manual V1.4 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/8 /2024 | Amend(Add GEN72 adapter files) | +|V1.2 | 9/10 /2024| Amend(Add ECO63 adapter files) | +|V1.3 | 25/12/2024| Amend(Add 63, 65, 75, ECO65 six-axis force adapter files and 63, 65, 75, ECO63, ECO65 integrated six-axis force adapter files) | +|V1.4 | 25/12/2024| Amend(Add GEN72_II adapter files) | + +
+ +## Content +* 1.[rm_bringup Package Description](#rm_bringup_Package_Description) +* 2.[rm_bringup Package Use](#rm_bringup_Package_Use) +* 2.1[moveit2 Controlling Real Robotic Arm](#moveit2_Controlling_Real_Robotic_Arm) +* 2.2[Gazebo control of robotic arm](#Gazebo_control_of_robotic_arm) +* 3.[rm_bringup Package Architecture Description](#rm_bringup_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4.[rm_bringup Topic Description](#rm_bringup_Topic_Description) + +## rm_bringup_Package_Description +rm_bringup is a function package for realizing the simultaneous running of multiple launch files. Using this package, a command can be used to launch complex functions combining multiple nodes. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address: https://github.com/RealManRobot/ros2_rm_robot.git。 +## rm_bringup_Package_Use +### moveit2_Controlling_Real_Robotic_Arm +First, after configuring the environment and completing the connection, we can directly launch the node and run the launch.py file in the rm_bringup package through the following command. +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__bringup.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, 75 and gen72. +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6f_bringup.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6fb_bringup.launch.py +``` +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm_65_bringup.launch.py +``` +The following screen appears in the interface after a successful node launch. +![image](doc/rm_bringup1.png) +The launch file launches the function of moveit2 to control the real robotic arm. Then, you can control the robotic arm movement by dragging the control ball. For details, please refer to "[rm_moveit2_config Detailed Description](https://github.com/RealManRobot/ros2_rm_robot/blob/main/rm_moveit2_config/README.md)". +### Gazebo_control_of_robotic_arm +We can run the launch.py file in the rm_bringup package through the following command, and directly launch the gzaebo simulation node. +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__gazebo.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65、eco63, 75, and gen72. + +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6f_gazebo.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6fb_gazebo.launch.py +``` +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm_65_gazebo.launch.py +``` +The following screen appears in the interface after a successful node launch. +![image](doc/rm_bringup2.png) +Then, we use the following command to launch moveit2 to control the simulation robot arm in Gazebo. +![image](doc/rm_bringup3.png) +## rm_bringup_Package_Architecture_Description +### Overview_of_Package_Files +The current rm_driver package is composed of the following files. +``` +├── CMakeLists.txt # compilation rule file +├── doc # Supporting documents,pictures +│ ├── rm_bringup1.png # pictures1 +│ ├── rm_bringup2.png # pictures2 +│ └── rm_bringup3.png # pictures3 +├── launch +│ ├── rm_63_6f_bringup.launch.py # 63 arm six-axis force moveit2 launch file +│ ├── rm_63_6f_gazebo.launch.py # 63 arm six-axis force gazebo launch file +│ ├── rm_63_6fb_bringup.launch.py # 63 arm integrated six-axis force moveit2 launch file +│ ├── rm_63_6fb_gazebo.launch.py # 63 arm integrated six-axis force gazebo launch file +│ ├── rm_63_bringup.launch.py # 63 arm moveit2 launch file +│ ├── rm_63_gazebo.launch.py # 63 arm gazebo launch file +│ ├── rm_65_6f_bringup.launch.py # 65 arm six-axis force moveit2 launch file +│ ├── rm_65_6f_gazebo.launch.py # 65 arm six-axis force gazebo launch file +│ ├── rm_65_6fb_bringup.launch.py # 65 arm integrated six-axis force moveit2 launch file +│ ├── rm_65_6fb_gazebo.launch.py # 65 arm integrated six-axis force gazebo launch file +│ ├── rm_65_bringup.launch.py # 65 arm moveit2 launch file +│ ├── rm_65_gazebo.launch.py # 65 arm gazebo launch file +│ ├── rm_75_6f_bringup.launch.py # 75 arm six-axis force moveit2 launch file +│ ├── rm_75_6f_gazebo.launch.py # 75 arm six-axis force gazebo launch file +│ ├── rm_75_6fb_bringup.launch.py # 75 arm integrated six-axis force moveit2 launch file +│ ├── rm_75_6fb_gazebo.launch.py # 75 arm integrated six-axis force gazebo launch file +│ ├── rm_75_bringup.launch.py # 75 arm moveit2 launch file +│ ├── rm_75_gazebo.launch.py # 75 arm gazebo launch file +│ ├── rm_eco63_6fb_bringup.launch.py # eco63 arm integrated six-axis force moveit2 launch file +│ ├── rm_eco63_6fb_gazebo.launch.py # eco63 arm integrated six-axis force gazebo launch file +│ ├── rm_eco63_bringup.launch.py # eco63 arm moveit2 launch file +│ ├── rm_eco63_gazebo.launch.py # eco63 arm gazebo launch file +│ ├── rm_eco65_6f_bringup.launch.py # eco65 arm six-axis force moveit2 launch file +│ ├── rm_eco65_6f_gazebo.launch.py # eco65 arm six-axis force gazebo launch file +│ ├── rm_eco65_6fb_bringup.launch.py # eco65 arm integrated six-axis force moveit2 launch file +│ ├── rm_eco65_6fb_gazebo.launch.py # eco65 arm integrated six-axis force gazebo launch file +│ ├── rm_eco65_bringup.launch.py # eco65 arm moveit2 launch file +│ ├── rm_eco65_gazebo.launch.py # eco65 arm gazebo launch file +│ ├── rm_gen72_bringup.launch.py # gen72 arm moveit2 launch file +│ └── rm_gen72_gazebo.launch.py # gen72 arm gazebo launch file +│ ├── rm_gen72_II_bringup.launch.py # gen72_II arm moveit2 launch file +│ └── rm_gen72_II_gazebo.launch.py # gen72_II arm gazebo launch file +├── package.xml +├── README_CN.md +└── README.md +``` +## rm_bringup_Topic_Description +This package currently does not have its topic. It is mainly to call other packages. For the topics related to moveit2, please refer to "[rm_moveit2_config Detailed Description](https://github.com/RealManRobot/ros2_rm_robot/blob/main/rm_moveit2_config/README.md)". diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README_CN.md new file mode 100644 index 0000000..7dbc12c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/README_CN.md @@ -0,0 +1,135 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_bringup/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_bringup/README.md) + +
+ +
+ +# 睿尔曼机器人rm_bringup使用说明书V1.4 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-8 |修订(添加GEN72适配文件) | +|V1.2 |2024-9-10 |修订(添加ECO63适配文件) | +|V1.3 |2024-12-25 |修订(添加了63、65、75、ECO65的六维力适配文件,以及63、65、75、ECO63、ECO65的一体化六维力适配文件) | +|V1.4 |2025-4-7 |修订(添加了GEN72_II适配文件) | + +
+ +## 目录 +* 1.[rm_bringup功能包说明](#rm_bringup功能包说明) +* 2.[rm_bringup功能包使用](#rm_bringup功能包使用) +* 2.1[moveit2控制真实机械臂](#moveit2控制真实机械臂) +* 2.2[控制gazebo仿真机械臂](#控制gazebo仿真机械臂) +* 3.[rm_bringup功能包架构说明](#rm_bringup功能包架构说明) +* 3.1[功能包文件总览](#rm_bringup功能包架构说明) +* 4.[rm_bringup话题说明](#rm_bringup话题说明) + +## rm_bringup功能包说明 +rm_bringup功能包为实现多个launch文件同时运行所设计的功能包,使用该功能包可用一条命令实现多个节点结合的复杂功能的启动。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用 +## rm_bringup功能包使用 +### moveit2控制真实机械臂 +首先配置好环境完成连接后我们可以通过以下命令直接启动节点,运行rm_bringup功能包中的launch.py文件。 +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__bringup.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72、gen72_II。 + +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6f_bringup.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6fb_bringup.launch.py +``` +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm_65_bringup.launch.py +``` +节点启动成功后,将弹出以下画面。 +![image](doc/rm_bringup1.png) +实际该launch文件启动的为moveit2控制真实机械臂的功能下面就可以使用控制球规划控制机械臂运动,详细可查看《[rm_moveit2_config详解]((https://github.com/RealManRobot/ros2_rm_robot/blob/main/rm_moveit2_config/README_CN.md))》相关内容。 +### 控制gazebo仿真机械臂 +我们可以通过以下命令运行rm_bringup功能包中的launch.py文件,直接启动其中的gzaebo仿真节点。 +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__gazebo.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72、gen72_II。 + +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6f_gazebo.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm__6fb_gazebo.launch.py +``` +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_bringup rm_65_gazebo.launch.py +``` +节点启动成功后,将弹出以下画面。 +![image](doc/rm_bringup2.png) +之后我们使用如下指令启动moveit2控制gazebo中的仿真机械臂。 +![image](doc/rm_bringup3.png) +## rm_bringup功能包架构说明 +### 功能包文件总览 +当前rm_bringup功能包的文件构成如下。 +``` +├── CMakeLists.txt #编译规则文件 +├── doc #辅助文档、图片存放文件夹 +│ ├── rm_bringup1.png #图片1 +│ ├── rm_bringup2.png #图片2 +│ └── rm_bringup3.png #图片3 +├── launch #启动文件 +│ ├── rm_63_6f_bringup.launch.py #63臂六维力moveit2启动文件 +│ ├── rm_63_6f_gazebo.launch.py #63臂六维力gazebo启动文件 +│ ├── rm_63_6fb_bringup.launch.py #63臂一体化六维力moveit2启动文件 +│ ├── rm_63_6fb_gazebo.launch.py #63臂一体化六维力gazebo启动文件 +│ ├── rm_63_bringup.launch.py #63臂moveit2启动文件 +│ ├── rm_63_gazebo.launch.py #63臂gazebo启动文件 +│ ├── rm_65_6f_bringup.launch.py #65臂六维力moveit2启动文件 +│ ├── rm_65_6f_gazebo.launch.py #65臂六维力gazebo启动文件 +│ ├── rm_65_6fb_bringup.launch.py #65臂一体化六维力moveit2启动文件 +│ ├── rm_65_6fb_gazebo.launch.py #65臂一体化六维力gazebo启动文件 +│ ├── rm_65_bringup.launch.py #65臂moveit2启动文件 +│ ├── rm_65_gazebo.launch.py #65臂gazebo启动文件 +│ ├── rm_75_6f_bringup.launch.py #75臂六维力moveit2启动文件 +│ ├── rm_75_6f_gazebo.launch.py #75臂六维力gazebo启动文件 +│ ├── rm_75_6fb_bringup.launch.py #75臂一体化六维力moveit2启动文件 +│ ├── rm_75_6fb_gazebo.launch.py #75臂一体化六维力gazebo启动文件 +│ ├── rm_75_bringup.launch.py #75臂moveit2启动文件 +│ ├── rm_75_gazebo.launch.py #75臂gazebo启动文件 +│ ├── rm_eco63_6fb_bringup.launch.py #eco63臂一体化六维力moveit2启动文件 +│ ├── rm_eco63_6fb_gazebo.launch.py #eco63臂一体化六维力gazebo启动文件 +│ ├── rm_eco63_bringup.launch.py #eco63臂moveit2启动文件 +│ ├── rm_eco63_gazebo.launch.py #eco63臂gazebo启动文件 +│ ├── rm_eco65_6f_bringup.launch.py #eco65臂六维力moveit2启动文件 +│ ├── rm_eco65_6f_gazebo.launch.py #eco65臂六维力gazebo启动文件 +│ ├── rm_eco65_6fb_bringup.launch.py #eco65臂一体化六维力moveit2启动文件 +│ ├── rm_eco65_6fb_gazebo.launch.py #eco65臂一体化六维力gazebo启动文件 +│ ├── rm_eco65_bringup.launch.py #eco65臂moveit2启动文件 +│ ├── rm_eco65_gazebo.launch.py #eco65臂gazebo启动文件 +│ ├── rm_gen72_bringup.launch.py #gen72臂moveit2启动文件 +│ ├── rm_gen72_gazebo.launch.py #gen72臂gazebo启动文件 +│ ├── rm_gen72_II_bringup.launch.py #gen72_II臂moveit2启动文件 +│ └── rm_gen72_II_gazebo.launch.py #gen72_II臂gazebo启动文件 +├── package.xml #依赖说明文件 +├── README_CN.md #中文说明文档 +└── README.md #英文说明文档 +``` +## rm_bringup话题说明 +该功能包当前并没有本身的话题,主要为调用其他功能包的话题实现,关于moveit2相关话题可查看《[rm_moveit2_config详解](https://github.com/RealManRobot/ros2_rm_robot/blob/main/rm_moveit2_config/README_CN.md)》相关内容。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup1.png new file mode 100644 index 0000000..9272fb1 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup2.png new file mode 100644 index 0000000..7582685 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup3.png new file mode 100644 index 0000000..d798eed Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/doc/rm_bringup3.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_bringup.launch.py new file mode 100644 index 0000000..db50a7b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_63_driver.launch.py')) + ) + + rm_63_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_63_6f_display.launch.py')), + ) + + rm_63_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_63_control.launch.py')) + ) + + rm_63_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'real_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_63_driver, + rm_63_description, + rm_63_control, + rm_63_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_gazebo.launch.py new file mode 100644 index 0000000..2d01283 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6f_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_63_6f_demo.launch.py')) + ) + + rm_63_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'gazebo_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_63_gazebo_up, + rm_63_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_bringup.launch.py new file mode 100644 index 0000000..4037082 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_63_driver.launch.py')) + ) + + rm_63_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_63_6fb_display.launch.py')), + ) + + rm_63_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_63_control.launch.py')) + ) + + rm_63_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'real_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_63_driver, + rm_63_description, + rm_63_control, + rm_63_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_gazebo.launch.py new file mode 100644 index 0000000..6eef226 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_6fb_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_63_6fb_demo.launch.py')) + ) + + rm_63_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'gazebo_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_63_gazebo_up, + rm_63_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_bringup.launch.py new file mode 100644 index 0000000..8db9476 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_63_driver.launch.py')) + ) + + rm_63_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_63_display.launch.py')), + ) + + rm_63_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_63_control.launch.py')) + ) + + rm_63_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_63_driver, + rm_63_description, + rm_63_control, + rm_63_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_gazebo.launch.py new file mode 100644 index 0000000..19eaab5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_63_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_63_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_63_demo.launch.py')) + ) + + rm_63_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_63_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_63_gazebo_up, + rm_63_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_bringup.launch.py new file mode 100644 index 0000000..47e57a0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_65_driver.launch.py')) + ) + + rm_65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_65_6f_display.launch.py')), + ) + + rm_65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_65_control.launch.py')) + ) + + rm_65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'real_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_65_driver, + rm_65_description, + rm_65_control, + rm_65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_gazebo.launch.py new file mode 100644 index 0000000..04d9524 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6f_gazebo.launch.py @@ -0,0 +1,25 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_65_6f_demo.launch.py')) + ) + rm_65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'gazebo_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_65_gazebo_up, + rm_65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_bringup.launch.py new file mode 100644 index 0000000..c128a4d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_65_driver.launch.py')) + ) + + rm_65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_65_6fb_display.launch.py')), + ) + + rm_65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_65_control.launch.py')) + ) + + rm_65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'real_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_65_driver, + rm_65_description, + rm_65_control, + rm_65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_gazebo.launch.py new file mode 100644 index 0000000..e8f572e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_6fb_gazebo.launch.py @@ -0,0 +1,25 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_65_6fb_demo.launch.py')) + ) + rm_65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'gazebo_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_65_gazebo_up, + rm_65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_bringup.launch.py new file mode 100644 index 0000000..622a898 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_65_driver.launch.py')) + ) + + rm_65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_65_display.launch.py')), + ) + + rm_65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_65_control.launch.py')) + ) + + rm_65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_65_driver, + rm_65_description, + rm_65_control, + rm_65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_gazebo.launch.py new file mode 100644 index 0000000..1875616 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_65_gazebo.launch.py @@ -0,0 +1,25 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_65_demo.launch.py')) + ) + rm_65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_65_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_65_gazebo_up, + rm_65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_bringup.launch.py new file mode 100644 index 0000000..949de36 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_75_driver.launch.py')) + ) + + rm_75_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_75_6f_display.launch.py')), + ) + + rm_75_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_75_control.launch.py')) + ) + + rm_75_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'real_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_75_driver, + rm_75_description, + rm_75_control, + rm_75_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_gazebo.launch.py new file mode 100644 index 0000000..a2486f4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6f_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_75_6f_demo.launch.py')) + ) + + rm_75_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'gazebo_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_75_gazebo_up, + rm_75_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_bringup.launch.py new file mode 100644 index 0000000..d67dc02 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_75_driver.launch.py')) + ) + + rm_75_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_75_6fb_display.launch.py')), + ) + + rm_75_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_75_control.launch.py')) + ) + + rm_75_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'real_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_75_driver, + rm_75_description, + rm_75_control, + rm_75_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_gazebo.launch.py new file mode 100644 index 0000000..590dcd0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_6fb_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_75_6fb_demo.launch.py')) + ) + + rm_75_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'gazebo_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_75_gazebo_up, + rm_75_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_bringup.launch.py new file mode 100644 index 0000000..cf61821 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_75_driver.launch.py')) + ) + + rm_75_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_75_display.launch.py')), + ) + + rm_75_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_75_control.launch.py')) + ) + + rm_75_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_75_driver, + rm_75_description, + rm_75_control, + rm_75_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_gazebo.launch.py new file mode 100644 index 0000000..768d94b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_75_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_75_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_75_demo.launch.py')) + ) + + rm_75_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_75_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_75_gazebo_up, + rm_75_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_bringup.launch.py new file mode 100644 index 0000000..a1a6a7a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco63_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_eco63_driver.launch.py')) + ) + + rm_eco63_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_eco63_6fb_display.launch.py')), + ) + + rm_eco63_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_eco63_control.launch.py')) + ) + + rm_eco63_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco63_config')),'launch', 'real_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_eco63_driver, + rm_eco63_description, + rm_eco63_control, + rm_eco63_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_gazebo.launch.py new file mode 100644 index 0000000..bf068fb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_6fb_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco63_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_eco63_6fb_demo.launch.py')) + ) + + rm_eco63_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco63_config')),'launch', 'gazebo_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_eco63_gazebo_up, + rm_eco63_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_bringup.launch.py new file mode 100644 index 0000000..794cc5d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco63_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_eco63_driver.launch.py')) + ) + + rm_eco63_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_eco63_display.launch.py')), + ) + + rm_eco63_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_eco63_control.launch.py')) + ) + + rm_eco63_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco63_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_eco63_driver, + rm_eco63_description, + rm_eco63_control, + rm_eco63_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_gazebo.launch.py new file mode 100644 index 0000000..8f225fa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco63_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco63_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_eco63_demo.launch.py')) + ) + + rm_eco63_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco63_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_eco63_gazebo_up, + rm_eco63_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_bringup.launch.py new file mode 100644 index 0000000..6be87d2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_eco65_driver.launch.py')) + ) + + rm_eco65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_eco65_6f_display.launch.py')), + ) + + rm_eco65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_eco65_control.launch.py')) + ) + + rm_eco65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'real_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_driver, + rm_eco65_description, + rm_eco65_control, + rm_eco65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_gazebo.launch.py new file mode 100644 index 0000000..24d469b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6f_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_eco65_6f_demo.launch.py')) + ) + + rm_eco65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'gazebo_moveit_demo_6f.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_gazebo_up, + rm_eco65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_bringup.launch.py new file mode 100644 index 0000000..89ce345 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_eco65_driver.launch.py')) + ) + + rm_eco65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_eco65_6fb_display.launch.py')), + ) + + rm_eco65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_eco65_control.launch.py')) + ) + + rm_eco65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'real_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_driver, + rm_eco65_description, + rm_eco65_control, + rm_eco65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_gazebo.launch.py new file mode 100644 index 0000000..61ae519 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_6fb_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_eco65_6fb_demo.launch.py')) + ) + + rm_eco65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'gazebo_moveit_demo_6fb.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_gazebo_up, + rm_eco65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_bringup.launch.py new file mode 100644 index 0000000..94c1865 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_eco65_driver.launch.py')) + ) + + rm_eco65_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_eco65_display.launch.py')), + ) + + rm_eco65_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_eco65_control.launch.py')) + ) + + rm_eco65_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_driver, + rm_eco65_description, + rm_eco65_control, + rm_eco65_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_gazebo.launch.py new file mode 100644 index 0000000..ef096fa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_eco65_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_eco65_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_eco65_demo.launch.py')) + ) + + rm_eco65_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_eco65_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_eco65_gazebo_up, + rm_eco65_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_bringup.launch.py new file mode 100644 index 0000000..cb0178a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_gen72_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_gen72_driver.launch.py')) + ) + + rm_gen72_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_gen72_II_display.launch.py')), + ) + + rm_gen72_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_gen72_control.launch.py')) + ) + + rm_gen72_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gen72_config')),'launch', 'real_moveit_demo_II.launch.py')) + ) + + return LaunchDescription([ + rm_gen72_driver, + rm_gen72_description, + rm_gen72_control, + rm_gen72_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_gazebo.launch.py new file mode 100644 index 0000000..ac04000 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_II_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_gen72_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_gen72_II_demo.launch.py')) + ) + + rm_gen72_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gen72_config')),'launch', 'gazebo_moveit_demo_II.launch.py')) + ) + + return LaunchDescription([ + rm_gen72_gazebo_up, + rm_gen72_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_bringup.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_bringup.launch.py new file mode 100644 index 0000000..24bc59a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_bringup.launch.py @@ -0,0 +1,36 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_gen72_driver = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_driver')),'launch', 'rm_gen72_driver.launch.py')) + ) + + rm_gen72_description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('rm_description'), 'launch', 'rm_gen72_display.launch.py')), + ) + + rm_gen72_control = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_control')),'launch', 'rm_gen72_control.launch.py')) + ) + + rm_gen72_moveit_config = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gen72_config')),'launch', 'real_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_gen72_driver, + rm_gen72_description, + rm_gen72_control, + rm_gen72_moveit_config + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_gazebo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_gazebo.launch.py new file mode 100644 index 0000000..5abdb2e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/launch/rm_gen72_gazebo.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import SetEnvironmentVariable +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.actions import (DeclareLaunchArgument, GroupAction, + IncludeLaunchDescription, SetEnvironmentVariable) +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + + rm_gen72_gazebo_up = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gazebo')),'launch', 'gazebo_gen72_demo.launch.py')) + ) + + rm_gen72_gazebo_moveit = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory(('rm_gen72_config')),'launch', 'gazebo_moveit_demo.launch.py')) + ) + + return LaunchDescription([ + rm_gen72_gazebo_up, + rm_gen72_gazebo_moveit + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/package.xml new file mode 100644 index 0000000..25b548b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_bringup/package.xml @@ -0,0 +1,18 @@ + + + + rm_bringup + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/CMakeLists.txt new file mode 100644 index 0000000..a72af51 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/CMakeLists.txt @@ -0,0 +1,60 @@ +cmake_minimum_required(VERSION 3.5) +project(rm_control) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +# if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") +# add_compile_options(-Wall -Wextra -Wpedantic) +# endif() +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(ament_cmake REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(actionlib_msgs REQUIRED) +find_package(control_msgs REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) + +include_directories( + ${PROJECT_SOURCE_DIR} + ${PROJECT_SOURCE_DIR}/include + ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME} +) + +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() +add_executable(rm_control src/rm_control.cpp) + +ament_target_dependencies(rm_control rclcpp std_msgs sensor_msgs rm_ros_interfaces rclcpp_action actionlib_msgs control_msgs) + +install(TARGETS +rm_control + DESTINATION lib/${PROJECT_NAME}) + +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README.md new file mode 100644 index 0000000..db64c74 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README.md @@ -0,0 +1,117 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_control/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_control/README.md) + +
+ +
+ +# RealMan Robot rm_control User Manual V1.2 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/8 /2024 | Amend(Add GEN72 adapter files) | +|V1.2 | 9/10 /2024| Amend(Add ECO63 adapter files) | +
+ +## Content +* 1.[rm_control Package Description](#rm_control_Package_Description) +* 2.[rm_control Package Function](#rm_control_Package_Function) +* 2.1[Basic use of the package](#Basic_use_of_the_package) +* 2.2[Advanced use of the package](#Advanced_use_of_the_package) +* 3.[rm_control Package Architecture Description](#rm_control_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4.[rm_control Topic Description](#rm_control_Topic_Description) + +## rm_control_Package_Description +rm_control is a function package for realizing the moveit2 control of a real robotic arm. The package is mainly used to further subdivide the path points planned by moveit2, and give the subdivided path points to rm_driver in a through-transmission way to realize the planning and running of the robotic arm. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address: https://github.com/RealManRobot/ros2_rm_robot.git。 +## rm_control_Package_Function +### Basic_use_of_the_package +First, after configuring the environment and completing the connection, we can directly start the node and run the rm_control package. +``` +rm@rm-desktop:~$ ros2 launch rm_control rm__control.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65、eco63, 75, and gen72. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_control rm_65_control.launch.py +``` +The following screen appears in the interface after successful node startup. +![image](doc/rm_control1.png) +It does not play a role when the node of the package is launched alone. It needs to be combined with the rm_driver package and the relevant nodes of moveit2 to play a role. For details, please refer to the relevant content of "rm_moveit2_config Detailed Description". +### Advanced_use_of_the_package +Some parameters can be configured in the rm_control package. Because there are not many parameters, the parameters are directly configured in the launch file. +![image](doc/rm_control2.png) +As shown in the figure above, the position of the first red box is the file path, and the position of the second box is the current configurable parameter. +Parameter follows: represents the following mode used by the current transmission, where true is high following and false is low following. The high following indicates that the robotic arm's movement mode is consistent with the transmission. It must do detailed calculations based on its transmission rate, speed, and acceleration. The threshold is set too high, but the control is fine. The low following indicates that the robotic arm moves to the transmission point based on its transmission rate, speed, and acceleration. If there are points that cannot be reached in time, there may be abandonment. The threshold is set low, and the control is not very fine but meets the use. +Parameter arm_type: represents the current model of the robotic arm. The parameters that can be selected are 65 (RM65 series), 651 (ECO65 series), 634 (ECO63 series), 632 (RM63 series), 75 (RM75 series) and 72 (GEN72 series). +In practice, we choose the corresponding launch file to start, which will automatically select the correct model. If there are special requirements, you can modify the corresponding parameters here. After modification, recompile the configuration in the workspace directory, and then the modified configuration will take effect. +Run colcon build command in the workspace directory. +``` +rm@rm-desktop: ~/ros2_ws$ colcon build +``` +After successful compilation, follow the above commands to start the package. +## rm_control_Package_Architecture_Description +### Overview_of_package_files +The current rm_control package is composed of the following files. +``` +├── CMakeLists.txt # compilation rule file +├── doc +│ ├── rm_control1.png +│ └── rm_control2.png +├── include # dependency header file folder +│ ├── cubicSpline.h # cubic spline interpolation header file +│ └── rm_control.h #rm_control header file +├── launch +│ ├── rm_63_control.launch.py # 63 launch file +│ ├── rm_65_control.launch.py # 65 launch file +│ ├── rm_75_control.launch.py # 75 launch file +│ ├── rm_eco65_control.launch.py # eco65 launch file +│ ├── rm_eco63_control.launch.py # eco63 launch file +│ └── rm_gen72_control.launch.py # gen72 launch file +├── package.xml # dependency declaration file +├── README_CN.md +├── README.md +└── src + └── rm_control.cpp # code source file +``` +## rm_control_Topic_Description +The following is the topic description of the package. +``` + Subscribers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /rm_driver/move_stop_cmd: std_msgs::msg::Bool + Publishers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /rm_driver/movej_canfd_cmd: rm_ros_interfaces/msg/Jointpos + /rosout: rcl_interfaces/msg/Log + Service Servers: + /rm_control/describe_parameters: rcl_interfaces/srv/DescribeParameters + /rm_control/get_parameter_types: rcl_interfaces/srv/GetParameterTypes + /rm_control/get_parameters: rcl_interfaces/srv/GetParameters + /rm_control/list_parameters: rcl_interfaces/srv/ListParameters + /rm_control/set_parameters: rcl_interfaces/srv/SetParameters + /rm_control/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically + Service Clients: + + Action Servers: + /rm_group_controller/follow_joint_trajectory: control_msgs/action/FollowJointTrajectory + Action Clients: +``` +We mainly focus on the following topics. +Publishers: represents its current published topic, the most important published topic is /rm_driver/movej_canfd_cmd, through which we publish the subdivided points to rm_driver node, and then rm_driver node gives the corresponding path to the robotic arm through the transmission way. +Action Servers: represents the action information it receives and publishes, /rm_group controller/follow_joint_trajectory action as the bridge of communication between rm_control and moveit2, through which rm_control receives the path planned by moveit2, and rm_control further subdivides these paths from the above topic to rm_driver. +There are relatively few remaining topics and service use scenarios, so we do not introduce them in detail here, and you can learn by yourself. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README_CN.md new file mode 100644 index 0000000..8c528aa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/README_CN.md @@ -0,0 +1,116 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_control/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_control/README.md) + +
+ +
+ +# 睿尔曼机器人rm_control使用说明书V1.2 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-3 |修订(添加GEN72相关适配文件) | +|V1.2 |2024-9-10 |修订(添加ECO63相关适配文件) | + +
+ +## 目录 +* 1.[rm_control功能包说明](#rm_control功能包说明) +* 2.[rm_control功能包使用](#rm_control功能包使用) +* 2.1[功能包基础使用](#功能包基础使用) +* 2.2[功能包进阶使用](#功能包进阶使用) +* 3.[rm_control功能包架构说明](#rm_control功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4.[rm_control话题说明](#rm_control话题说明) + +## rm_control功能包说明 +rm_control功能包为实现moveit2控制真实机械臂时所必须的一个功能包,该功能包的主要作用为将moveit2规划好的路径点进行进一步的细分,将细分后的路径点以透传的方式给到rm_driver,实现机械臂的规划运行。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用 +## rm_control功能包使用 +### 功能包基础使用 +首先配置好环境完成连接后我们可以通过以下命令直接启动节点,运行rm_control功能包。 +``` +rm@rm-desktop:~$ ros2 launch rm_control rm__control.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_control rm_65_control.launch.py +``` +节点启动成功后,将显示以下画面。 +![image](doc/rm_control1.png) +在单独启动该功能包的节点时并不发挥作用,需要结合rm_driver功能包和moveit2的相关节点一起使用才能发挥作用,详细请查看《rm_moveit2_config详解》相关内容。 +### 功能包进阶使用 +在rm_control功能包中也有一些参数可以进行配置,由于参数并不是很多,这边将参数直接在launch文件中进行了配置。 +![image](doc/rm_control2.png) +如上图所示第一个红框框出的位置为文件的路径,第二个框出的位置为当前可配置的参数。 +参数follow:代表当前透传使用的跟随模式,true:高跟随,false:低跟随。高跟随即机械臂运动方式与透传完全一致,需要根据透传的速率和机械臂的速度、加速度参数进行较详细的计算,使用门槛较高,但控制精细。低跟随即机械臂会基本根据透传速率和速度、加速度向透传点运动,若有来不及到达的点可能会有丢弃现象发生,使用门槛低,控制不太精细,但基本满足使用。 +参数arm_type:代表当前使用的机械臂型号,可以选择的参数有65(RM65系列)、651(ECO65系列)、634(ECO63系列)、632(63系列)、634(ECO63系列)、75(75系列)72(GEN72系列)。 +再实际使用时,我们选择对应的launch文件启动时会自动选择正确的型号,若有特殊要求可在此处进行相应的参数修改,修改之后需要在工作空间目录下进行重新编译,之后修改的配置才会生效。 +在工作空间目录运行colcon build指令。 +``` +rm@rm-desktop: ~/ros2_ws$ colcon build +``` +编译成功后可按如上指令进行功能包启动。 +## rm_control功能包架构说明 +### 功能包文件总览 +当前rm_control功能包的文件构成如下。 +``` +├── CMakeLists.txt #编译规则文件 +├── doc #辅助文档、图片存放文件夹 +│ ├── rm_control1.png +│ └── rm_control2.png +├── include #依赖头文件文件夹 +│ ├── cubicSpline.h #三次样条插值头文件 +│ └── rm_control.h #rm_control头文件 +├── launch +│ ├── rm_63_control.launch.py #63启动文件 +│ ├── rm_65_control.launch.py #65启动文件 +│ ├── rm_75_control.launch.py #75启动文件 +│ ├── rm_eco65_control.launch.py #eco65启动文件 +│ ├── rm_eco63_control.launch.py #eco63启动文件 +│ └── rm_gen72_control.launch.py #gen72启动文件 +├── package.xml #依赖声明文件 +├── README_CN.md +├── README.md +└── src + └── rm_control.cpp #代码源文件 +``` +## rm_control话题说明 +如下为该功能包的话题说明。 +``` + Subscribers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /rm_driver/move_stop_cmd: std_msgs::msg::Bool + Publishers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /rm_driver/movej_canfd_cmd: rm_ros_interfaces/msg/Jointpos + /rosout: rcl_interfaces/msg/Log + Service Servers: + /rm_control/describe_parameters: rcl_interfaces/srv/DescribeParameters + /rm_control/get_parameter_types: rcl_interfaces/srv/GetParameterTypes + /rm_control/get_parameters: rcl_interfaces/srv/GetParameters + /rm_control/list_parameters: rcl_interfaces/srv/ListParameters + /rm_control/set_parameters: rcl_interfaces/srv/SetParameters + /rm_control/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically + Service Clients: + + Action Servers: + /rm_group_controller/follow_joint_trajectory: control_msgs/action/FollowJointTrajectory + Action Clients: +``` +我们主要关注以下几个话题。 +Publishers:代表其当前发布的话题,其最主要发布的话题为/rm_driver/movej_canfd_cmd,我们通过该话题将细分后的点发布给rm_driver节点,rm_driver节点再通过透传的指令方式给到机械臂执行相对应的路径。 +Action Servers:代表其接受和发布的动作信息,/rm_group_controller/follow_joint_trajectory动作为rm_control与moveit2进行通信的桥梁,通过该动作rm_control接收到moveit2规划的路径,rm_control会将这些路径进行进一步细分由以上话题给到rm_driver。 +剩余话题和服务使用场景较少,这里不做详细介绍,大家可自行了解。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control1.png new file mode 100644 index 0000000..89debb8 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control2.png new file mode 100644 index 0000000..5cfd1f6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/doc/rm_control2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/cubicSpline.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/cubicSpline.h new file mode 100644 index 0000000..c317871 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/cubicSpline.h @@ -0,0 +1,34 @@ +#ifndef _CUBIC_SPLINE_H_ +#define _CUBIC_SPLINE_H_ +// #define RAD_DEGREE 57.2958 + +class cubicSpline +{ +public: + typedef enum _BoundType + { + BoundType_First_Derivative, + BoundType_Second_Derivative + }BoundType; + +public: + cubicSpline(); + ~cubicSpline(); + + void initParam(); + void releaseMem(); + + bool loadData(double *x_data, double *y_data, int count, double bound1, double bound2, BoundType type); + bool getYbyX(double &x_in, double &y_out); + +protected: + bool spline(BoundType type); + +protected: + double *x_sample_, *y_sample_; + double *M_; + int sample_count_; + double bound1_, bound2_; +}; + +#endif /* _CUBIC_SPLINE_H_ */ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/rm_control.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/rm_control.h new file mode 100644 index 0000000..9097860 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/include/rm_control.h @@ -0,0 +1,58 @@ +#ifndef RM_CONTROL_H +#define RM_CONTROL_H + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_action/rclcpp_action.hpp" + +#include +#include "control_msgs/action/follow_joint_trajectory.hpp" +#include +#include + +//RM Robot msg +#include "rm_ros_interfaces/msg/jointpos.hpp" +//#include "rm_ros_interfaces/msg/jointpos75.hpp" + +/* 使用变长数组 */ +#include +#include + +using namespace std; + +class Rm_Control : public rclcpp::Node +{ +public: + using FollowJointTrajectory = control_msgs::action::FollowJointTrajectory; + using GoalHandleFJT = rclcpp_action::ServerGoalHandle; + + explicit Rm_Control(std::string name); + ~Rm_Control(){} + + void timer_callback(); + +private: + rm_ros_interfaces::msg::Jointpos joint_msg; + // rm_ros_interfaces::msg::Jointpos75 joint7_msg; + int arm_type_ = 75; + bool follow_ = false; + // 实例化样条 + rclcpp_action::Server::SharedPtr action_server_; + + // 声明话题发布者 + rclcpp::Publisher::SharedPtr joint_pos_publisher; + // rclcpp::Publisher::SharedPtr joint_pos_publisher_75; + + //声明话题订阅者 + rclcpp::Subscription::SharedPtr Get_Move_Stop_Cmd; + + rclcpp::TimerBase::SharedPtr State_Timer; + + rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr goal); + rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr goal_handle); + void execute_move(const std::shared_ptr goal_handle); + void handle_accepted(const std::shared_ptr goal_handle); + void get_move_stop_callback(std_msgs::msg::Bool::SharedPtr msg); +}; + +#endif // Rm_Control_H + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_63_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_63_control.launch.py new file mode 100644 index 0000000..f9d4bbd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_63_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': False}, + {'arm_type': 632} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_65_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_65_control.launch.py new file mode 100644 index 0000000..62dd920 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_65_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': False}, + {'arm_type': 65} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_75_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_75_control.launch.py new file mode 100644 index 0000000..f50f531 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_75_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': True}, + {'arm_type': 75} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco63_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco63_control.launch.py new file mode 100644 index 0000000..5bf3b20 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco63_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': False}, + {'arm_type': 634} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco65_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco65_control.launch.py new file mode 100644 index 0000000..bee88c2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_eco65_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': False}, + {'arm_type': 651} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_gen72_control.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_gen72_control.launch.py new file mode 100644 index 0000000..a8ea2db --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/launch/rm_gen72_control.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + control_node = Node( + package='rm_control', #节点所在的功能包 + executable='rm_control', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'follow': True}, + {'arm_type': 72} + ], #接入参数文件 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(control_node) + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/package.xml new file mode 100644 index 0000000..a63bf05 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/package.xml @@ -0,0 +1,23 @@ + + + + rm_control + 0.0.0 + TODO: Package description + xtark + TODO: License declaration + + ament_cmake + + rclcpp + + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/src/rm_control.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/src/rm_control.cpp new file mode 100644 index 0000000..5169fbd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_control/src/rm_control.cpp @@ -0,0 +1,743 @@ + +//* ROS action server */ +#include "rm_control.h" +/* 三次样条插补 */ +#include "cubicSpline.h" + +using namespace std; +vector time_from_start_; +vector p_joint1_; +vector p_joint2_; +vector p_joint3_; +vector p_joint4_; +vector p_joint5_; +vector p_joint6_; +vector p_joint7_; +vector v_joint1_; +vector v_joint2_; +vector v_joint3_; +vector v_joint4_; +vector v_joint5_; +vector v_joint6_; +vector v_joint7_; +vector a_joint1_; +vector a_joint2_; +vector a_joint3_; +vector a_joint4_; +vector a_joint5_; +vector a_joint6_; +vector a_joint7_; + +/* 存储的结构体 p2*/ +struct vel_data +{ + int vector_len; //toatal num + int vector_cnt; //current num +}; + +/* 数据收发结构体 */ +struct vel_data p2; + +/* action 服务端声明 */ +// typedef actionlib::SimpleActionServer Server; + +/* 初始化输入输出速度加速度 */ +double acc = 0, vel = 0; +double x_out = 0, y_out = 0; + +/* 判断路点数据是否改变 */ +bool point_changed = false; + +/*三次样条插值后周期*/ +double rate = 0.020; // 5ms + +float min_interval = 20; //透传周期,单位:秒 +float wait_move_finish_time = 1.5; //等待运动到位时间,单位:秒 +int count_keep_send = 0; +int count_final_joint = 0; + +/* 三次样条无参构造 */ +cubicSpline::cubicSpline() +{ +} +/* 析构 */ +cubicSpline::~cubicSpline() +{ + releaseMem(); +} +/* 初始化参数 */ +void cubicSpline::initParam() +{ + x_sample_ = y_sample_ = M_ = NULL; + sample_count_ = 0; + bound1_ = bound2_ = 0; +} +/* 释放参数 */ +void cubicSpline::releaseMem() +{ + delete x_sample_; + delete y_sample_; + delete M_; + + initParam(); +} +/* 加载关节位置数组等信息 */ +bool cubicSpline::loadData(double *x_data, double *y_data, int count, double bound1, double bound2, BoundType type) +{ + if ((NULL == x_data) || (NULL == y_data) || (count < 3) || (type > BoundType_Second_Derivative) || (type < BoundType_First_Derivative)) + { + return false; + } + initParam(); + + x_sample_ = new double[count]; + y_sample_ = new double[count]; + M_ = new double[count]; + sample_count_ = count; + + memcpy(x_sample_, x_data, sample_count_*sizeof(double)); + memcpy(y_sample_, y_data, sample_count_*sizeof(double)); + + bound1_ = bound1; + bound2_ = bound2; + + return spline(type); +} +/* 计算样条插值 */ +bool cubicSpline::spline(BoundType type) +{ + if ((type < BoundType_First_Derivative) || (type > BoundType_Second_Derivative)) + { + return false; + } + + // 追赶法解方程求二阶偏导数 + double f1=bound1_, f2=bound2_; + + double *a=new double[sample_count_]; // a:稀疏矩阵最下边一串数 + double *b=new double[sample_count_]; // b:稀疏矩阵最中间一串数 + double *c=new double[sample_count_]; // c:稀疏矩阵最上边一串数 + double *d=new double[sample_count_]; + + double *f=new double[sample_count_]; + + double *bt=new double[sample_count_]; + double *gm=new double[sample_count_]; + + double *h=new double[sample_count_]; + + for(int i=0;i=0;i--) + M_[i]=gm[i]-bt[i]*M_[i+1]; + } + else if(BoundType_Second_Derivative == type) + { + d[1]=d[1]-a[1]*f1; + d[sample_count_-2]=d[sample_count_-2]-c[sample_count_-2]*f2; + + bt[1]=c[1]/b[1]; + for(int i=2;i=1;i--) + M_[i]=gm[i]-bt[i]*M_[i+1]; + + M_[0]=f1; + M_[sample_count_-1]=f2; + } + else + return false; + + delete a; + delete b; + delete c; + delete d; + delete gm; + delete bt; + delete f; + delete h; + + return true; +} +/* 得到速度和加速度数组 */ +bool cubicSpline::getYbyX(double &x_in, double &y_out) +{ + int klo,khi,k; + klo=0; + khi=sample_count_-1; + double hh,bb,aa; + + // 二分法查找x所在区间段 + while(khi-klo>1) + { + k=(khi+klo)>>1; + if(x_sample_[k]>x_in) + khi=k; + else + klo=k; + } + hh=x_sample_[khi]-x_sample_[klo]; + + aa=(x_sample_[khi]-x_in)/hh; + bb=(x_in-x_sample_[klo])/hh; + + y_out=aa*y_sample_[klo]+bb*y_sample_[khi]+((aa*aa*aa-aa)*M_[klo]+(bb*bb*bb-bb)*M_[khi])*hh*hh/6.0; + + //test + acc = (M_[klo]*(x_sample_[khi]-x_in) + M_[khi]*(x_in - x_sample_[klo])) / hh; + vel = M_[khi]*(x_in - x_sample_[klo]) * (x_in - x_sample_[klo]) / (2 * hh) + - M_[klo]*(x_sample_[khi]-x_in) * (x_sample_[khi]-x_in) / (2 * hh) + + (y_sample_[khi] - y_sample_[klo])/hh + - hh*(M_[khi] - M_[klo])/6; + + return true; +} + + +Rm_Control::Rm_Control(std::string name) : Node(name) +{ + + using namespace std::placeholders; + + + this->declare_parameter("arm_type", arm_type_); + this->get_parameter("arm_type", arm_type_); + + this->declare_parameter("follow", follow_); + this->get_parameter("follow", follow_); + + if((arm_type_ == 75)||(arm_type_ == 72)) + { + joint_msg.joint.resize(7); + joint_msg.dof = 7; + arm_type_ = 75; + } + else + { + joint_msg.joint.resize(6); + joint_msg.dof = 6; + } + + State_Timer = this->create_wall_timer(std::chrono::milliseconds(20), + std::bind(&Rm_Control::timer_callback,this)); + + this->action_server_ = rclcpp_action::create_server( + this, "/rm_group_controller/follow_joint_trajectory", + std::bind(&Rm_Control::handle_goal, this, _1, _2), + std::bind(&Rm_Control::handle_cancel, this, _1), + std::bind(&Rm_Control::handle_accepted, this, _1)); + + rclcpp::QoS qos(10); + + joint_pos_publisher = this->create_publisher("/rm_driver/movej_canfd_cmd", qos); + + Get_Move_Stop_Cmd = this->create_subscription("rm_driver/move_stop_cmd",rclcpp::ParametersQoS(), + std::bind(&Rm_Control::get_move_stop_callback,this,std::placeholders::_1)); + +} + +rclcpp_action::GoalResponse Rm_Control::handle_goal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr goal) +{ + std::cout << "---handle goal:" << goal->trajectory.joint_names.size() << std::endl; + std::cout << goal->trajectory.header.frame_id.c_str() << goal->trajectory.header.stamp.sec << goal->trajectory.header.stamp.nanosec << std::endl; + + int pointSize = goal->trajectory.points.size(); + if(pointSize > 0) + { + for(int i = 0; i < pointSize; i++) + { + auto point = goal->trajectory.points.at(i); + } + } + + (void)uuid; + + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + +rclcpp_action::CancelResponse Rm_Control::handle_cancel(const std::shared_ptr goal_handle) +{ + RCLCPP_INFO(this->get_logger(), "Received request to cancel goal"); + + return rclcpp_action::CancelResponse::ACCEPT; +} + +void Rm_Control::handle_accepted(const std::shared_ptr goal_handle) +{ + using std::placeholders::_1; + + std::thread{std::bind(&Rm_Control::execute_move, this, _1), goal_handle} + .detach(); +} + +/* 收到action的goal后调用的回调函数 */ +void Rm_Control::execute_move(const std::shared_ptr goal_handle) +{ + int i = 0; + const auto goal = goal_handle->get_goal(); + auto result = std::make_shared(); + int point_num = goal->trajectory.points.size(); + RCLCPP_INFO(this->get_logger(), "First Move_group give us %d points",point_num); + point_changed = false; + + /***********Start gubs 2021/9/16 修复Moveit在同一位姿重复规划执行导致rm_contorl异常停止的Bug***********/ + if (point_num > 3) //判断当moveit规划的路点数大于3时为有效规划并进行三次样条插值 + { + + /* 各个关节位置 */ + double p_joint1[point_num]; + double p_joint2[point_num]; + double p_joint3[point_num]; + double p_joint4[point_num]; + double p_joint5[point_num]; + double p_joint6[point_num]; + double p_joint7[point_num]; + + /* 各个关节速度 */ + double v_joint1[point_num]; + double v_joint2[point_num]; + double v_joint3[point_num]; + double v_joint4[point_num]; + double v_joint5[point_num]; + double v_joint6[point_num]; + double v_joint7[point_num]; + + /* 各个关节加速度 */ + double a_joint1[point_num]; + double a_joint2[point_num]; + double a_joint3[point_num]; + double a_joint4[point_num]; + double a_joint5[point_num]; + double a_joint6[point_num]; + double a_joint7[point_num]; + + /* 时间数组 */ + double time_from_start[point_num]; + double timens_from_start[point_num]; + + for (i = 0; i < point_num; i++) + { + p_joint1[i] = goal->trajectory.points[i].positions[0]; + p_joint2[i] = goal->trajectory.points[i].positions[1]; + p_joint3[i] = goal->trajectory.points[i].positions[2]; + p_joint4[i] = goal->trajectory.points[i].positions[3]; + p_joint5[i] = goal->trajectory.points[i].positions[4]; + p_joint6[i] = goal->trajectory.points[i].positions[5]; + if(arm_type_ == 75) + { + p_joint7[i] = goal->trajectory.points[i].positions[6]; + } + + + v_joint1[i] = goal->trajectory.points[i].velocities[0]; + v_joint2[i] = goal->trajectory.points[i].velocities[1]; + v_joint3[i] = goal->trajectory.points[i].velocities[2]; + v_joint4[i] = goal->trajectory.points[i].velocities[3]; + v_joint5[i] = goal->trajectory.points[i].velocities[4]; + v_joint6[i] = goal->trajectory.points[i].velocities[5]; + if(arm_type_ == 75) + { + v_joint7[i] = goal->trajectory.points[i].velocities[6]; + } + + a_joint1[i] = goal->trajectory.points[i].accelerations[0]; + a_joint2[i] = goal->trajectory.points[i].accelerations[1]; + a_joint3[i] = goal->trajectory.points[i].accelerations[2]; + a_joint4[i] = goal->trajectory.points[i].accelerations[3]; + a_joint5[i] = goal->trajectory.points[i].accelerations[4]; + a_joint6[i] = goal->trajectory.points[i].accelerations[5]; + if(arm_type_ == 75) + { + a_joint7[i] = goal->trajectory.points[i].accelerations[6]; + } + + time_from_start[i] = goal->trajectory.points[i].time_from_start.sec + goal->trajectory.points[i].time_from_start.nanosec/1e9; + timens_from_start[i] = goal->trajectory.points[i].time_from_start.nanosec; + + } + cubicSpline spline; + double max_time = time_from_start[point_num-1]; + RCLCPP_INFO(this->get_logger(), "Second Move_group max_time is %f", max_time); + time_from_start_.clear(); + + // joint1 + if (spline.loadData(time_from_start, p_joint1, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint1_.clear(); + v_joint1_.clear(); + a_joint1_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + time_from_start_.push_back(x_out); // 将新的时间存储,只需操作一次即可 + p_joint1_.push_back(y_out); + v_joint1_.push_back(vel); + a_joint1_.push_back(acc); + } + + // joint2 + if (spline.loadData(time_from_start, p_joint2, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + + p_joint2_.clear(); + v_joint2_.clear(); + a_joint2_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint2_.push_back(y_out); + v_joint2_.push_back(vel); + a_joint2_.push_back(acc); + } + + // joint3 + if (spline.loadData(time_from_start, p_joint3, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint3_.clear(); + v_joint3_.clear(); + a_joint3_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint3_.push_back(y_out); + v_joint3_.push_back(vel); + a_joint3_.push_back(acc); + } + + // joint4 + if (spline.loadData(time_from_start, p_joint4, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint4_.clear(); + v_joint4_.clear(); + a_joint4_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint4_.push_back(y_out); + v_joint4_.push_back(vel); + a_joint4_.push_back(acc); + } + + // joint5 + if (spline.loadData(time_from_start, p_joint5, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint5_.clear(); + v_joint5_.clear(); + a_joint5_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint5_.push_back(y_out); + v_joint5_.push_back(vel); + a_joint5_.push_back(acc); + } + + // joint6 + if (spline.loadData(time_from_start, p_joint6, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint6_.clear(); + v_joint6_.clear(); + a_joint6_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint6_.push_back(y_out); + v_joint6_.push_back(vel); + a_joint6_.push_back(acc); + } + + // joint7 + if(arm_type_ == 75) + { + if (spline.loadData(time_from_start, p_joint7, point_num, 0, 0, cubicSpline::BoundType_First_Derivative)) + { + p_joint7_.clear(); + v_joint7_.clear(); + a_joint7_.clear(); + x_out = -rate; + while(x_out < max_time) { + x_out += rate; + spline.getYbyX(x_out, y_out); + p_joint7_.push_back(y_out); + v_joint7_.push_back(vel); + a_joint7_.push_back(acc); + } + + + p2.vector_len = time_from_start_.size(); + p2.vector_cnt = 0; + + point_changed = true; + //等待定时器将数据取出并发送完 + while(point_changed) + { + // ros::WallDuration(0.002).sleep(); + if (!rclcpp::ok() || goal_handle->is_canceling()) + { + result->error_code = -1; + result->error_string = "has cancel"; + goal_handle->canceled(result); + RCLCPP_INFO(this->get_logger(), "Goal Canceled"); + return; + } + } + } + + } + else + { + p2.vector_len = time_from_start_.size(); + p2.vector_cnt = 0; + + point_changed = true; + //等待定时器将数据取出并发送完 + while(point_changed) + { + // ros::WallDuration(0.002).sleep(); + if (!rclcpp::ok() || goal_handle->is_canceling()) + { + result->error_code = -1; + result->error_string = "has cancel"; + goal_handle->canceled(result); + RCLCPP_INFO(this->get_logger(), "Goal Canceled"); + return; + } + } + } + } + } + } + } + } + + } + } + + else if (point_num > 0) + { + p_joint1_.clear(); + v_joint1_.clear(); + a_joint1_.clear(); + p_joint2_.clear(); + v_joint2_.clear(); + a_joint2_.clear(); + p_joint3_.clear(); + v_joint3_.clear(); + a_joint3_.clear(); + p_joint4_.clear(); + v_joint4_.clear(); + a_joint4_.clear(); + p_joint5_.clear(); + v_joint5_.clear(); + a_joint5_.clear(); + p_joint6_.clear(); + v_joint6_.clear(); + a_joint6_.clear(); + if(arm_type_ == 75) + { + p_joint7_.clear(); + v_joint7_.clear(); + a_joint7_.clear(); + } + for (int i = 0; i < point_num; i++) { + p_joint1_.push_back(goal->trajectory.points[i].positions[0]); + v_joint1_.push_back(goal->trajectory.points[i].velocities[0]); + a_joint1_.push_back(goal->trajectory.points[i].accelerations[0]); + p_joint2_.push_back(goal->trajectory.points[i].positions[1]); + v_joint2_.push_back(goal->trajectory.points[i].velocities[1]); + a_joint2_.push_back(goal->trajectory.points[i].accelerations[1]); + p_joint3_.push_back(goal->trajectory.points[i].positions[2]); + v_joint3_.push_back(goal->trajectory.points[i].velocities[2]); + a_joint3_.push_back(goal->trajectory.points[i].accelerations[2]); + p_joint4_.push_back(goal->trajectory.points[i].positions[3]); + v_joint4_.push_back(goal->trajectory.points[i].velocities[3]); + a_joint4_.push_back(goal->trajectory.points[i].accelerations[3]); + p_joint5_.push_back(goal->trajectory.points[i].positions[4]); + v_joint5_.push_back(goal->trajectory.points[i].velocities[4]); + a_joint5_.push_back(goal->trajectory.points[i].accelerations[4]); + p_joint6_.push_back(goal->trajectory.points[i].positions[5]); + v_joint6_.push_back(goal->trajectory.points[i].velocities[5]); + a_joint6_.push_back(goal->trajectory.points[i].accelerations[5]); + if(arm_type_ == 75) + { + p_joint7_.push_back(goal->trajectory.points[i].positions[6]); + v_joint7_.push_back(goal->trajectory.points[i].velocities[6]); + a_joint7_.push_back(goal->trajectory.points[i].accelerations[6]); + } + } + p2.vector_len = point_num; + p2.vector_cnt = 0; + + point_changed = true; + //等待定时器将数据取出并发送完 + while(point_changed) + { + // ros::WallDuration(0.002).sleep(); + if (!rclcpp::ok() || goal_handle->is_canceling()) + { + result->error_code = -1; + result->error_string = "has cancel"; + goal_handle->canceled(result); + RCLCPP_INFO(this->get_logger(), "Goal Canceled"); + return; + } + } + } + + result->error_code = 0; + result->error_string = ""; + + goal_handle->succeed(result); + RCLCPP_INFO(this->get_logger(), "Goal Succeeded"); +} + +void Rm_Control::timer_callback() +{ + + joint_msg.follow = follow_; + + + if(point_changed) + { + if(p2.vector_cnt < p2.vector_len) + { + // RCLCPP_INFO(this->get_logger(), "Pos:[%f, %f, %f, %f, %f, %f]", p_joint1_.at(p2.vector_cnt), p_joint2_.at(p2.vector_cnt), p_joint3_.at(p2.vector_cnt), p_joint4_.at(p2.vector_cnt), p_joint5_.at(p2.vector_cnt), p_joint6_.at(p2.vector_cnt)); + if(arm_type_ == 75) + { + joint_msg.joint[0] = p_joint1_.at(p2.vector_cnt); + joint_msg.joint[1] = p_joint2_.at(p2.vector_cnt); + joint_msg.joint[2] = p_joint3_.at(p2.vector_cnt); + joint_msg.joint[3] = p_joint4_.at(p2.vector_cnt); + joint_msg.joint[4] = p_joint5_.at(p2.vector_cnt); + joint_msg.joint[5] = p_joint6_.at(p2.vector_cnt); + joint_msg.joint[6] = p_joint7_.at(p2.vector_cnt); + this->joint_pos_publisher->publish(joint_msg); + } + else + { + joint_msg.joint[0] = p_joint1_.at(p2.vector_cnt); + joint_msg.joint[1] = p_joint2_.at(p2.vector_cnt); + joint_msg.joint[2] = p_joint3_.at(p2.vector_cnt); + joint_msg.joint[3] = p_joint4_.at(p2.vector_cnt); + joint_msg.joint[4] = p_joint5_.at(p2.vector_cnt); + joint_msg.joint[5] = p_joint6_.at(p2.vector_cnt); + this->joint_pos_publisher->publish(joint_msg); + } + + p2.vector_cnt++; + } + else + { + if(count_final_joint <= count_keep_send) + { + if(arm_type_ == 75) + { + joint_msg.joint[0] = p_joint1_.at(p2.vector_cnt-1); + joint_msg.joint[1] = p_joint2_.at(p2.vector_cnt-1); + joint_msg.joint[2] = p_joint3_.at(p2.vector_cnt-1); + joint_msg.joint[3] = p_joint4_.at(p2.vector_cnt-1); + joint_msg.joint[4] = p_joint5_.at(p2.vector_cnt-1); + joint_msg.joint[5] = p_joint6_.at(p2.vector_cnt-1); + joint_msg.joint[6] = p_joint7_.at(p2.vector_cnt-1); + this->joint_pos_publisher->publish(joint_msg); + } + else + { + joint_msg.joint[0] = p_joint1_.at(p2.vector_cnt-1); + joint_msg.joint[1] = p_joint2_.at(p2.vector_cnt-1); + joint_msg.joint[2] = p_joint3_.at(p2.vector_cnt-1); + joint_msg.joint[3] = p_joint4_.at(p2.vector_cnt-1); + joint_msg.joint[4] = p_joint5_.at(p2.vector_cnt-1); + joint_msg.joint[5] = p_joint6_.at(p2.vector_cnt-1); + this->joint_pos_publisher->publish(joint_msg); + } + count_final_joint++; + } + else + { + count_final_joint = 0; + p2.vector_cnt = 0; + p2.vector_len = 0; + point_changed = false; + } + } + } +} + +void Rm_Control::get_move_stop_callback(const std_msgs::msg::Bool::SharedPtr msg) +{ + bool result; + result = msg->data; + point_changed=false; + //RCLCPP_INFO(this->get_logger(), "move stop is true!!! "); +} +/* 主函数主要用于动作订阅和套接字通信 */ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + count_keep_send = wait_move_finish_time / min_interval; + rclcpp::spin(std::make_shared("rm_control")); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/CMakeLists.txt new file mode 100644 index 0000000..52892f6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +project(rm_description) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +install( + DIRECTORY launch urdf meshes + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README.md new file mode 100644 index 0000000..fb37cdc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README.md @@ -0,0 +1,236 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_description/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_description/README.md) + +
+ +
+ +# RealMan Robot rm_description User Manual V1.4 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/8 /2024 | Amend(Add GEN72 adapter files) | +|V1.2 | 9/11 /2024| Amend(Add ECO63 adapter files) | +|V1.3 | 25/12/2024| Amend(Add 63, 65, 75, ECO65 six-axis force adapter files and 63, 65, 75, ECO63, ECO65 integrated six-axis force adapter files) | +|V1.4 |2025-4-7 |Amend(AddGEN72_II adapter files) | +
+ +## Content +* 1.[rm_description Package Description](#rm_description_Package_Description) +* 2.[rm_description Package Use](#rm_description_Package_Use) +* 3.[rm_description Package Architecture Description](#rm_description_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4.[rm_description Topic Description](#rm_description_Topic_Description) + +## rm_description_Package_Description +rm_description is a function package for displaying the robot model and TF transformation. Through this package, we can realize the linkage effect between a virtual robotic arm in a computer and a real robot arm in reality. In the moveit2 control, we also need the support of this package. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address:https://github.com/RealManRobot/ros2_rm_robot.git. +## rm_description_Package_Use +First, after configuring the environment and completing the connection, we can directly start the node and run the rm_description package. +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__display.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, 75, and gen72. + +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6f_display.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6fb_display.launch.py +``` +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_description rm_65_display.launch.py +``` +The following screen appears in the interface after successful node startup. +![image](doc/rm_description2.png) +Then we need to launch the rm_driver node. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +After a successful launch, we can check the state of the robotic arm in rviz2. Run the following command to launch rviz2. +``` +rm@rm-desktop:~$ rviz2 +``` +Open the robot model with the following configuration. +![image](doc/rm_description3.png) +Find the corresponding configuration file under the rviz folder of the rm_description package. +![image](doc/rm_description4.png) +After loading, you can see the current state of the robotic arm in the interface of rviz2. +![image](doc/rm_description1.png) +## rm_description_Package_Architecture_Description +### Overview_of_package_files +The current rm_description package is composed of the following files. +``` +├── CMakeLists.txt # compilation rule file +├── launch +│ ├── rm_63_6f_display.launch.py # 63 six-axis force launch file +│ ├── rm_63_6fb_display.launch.py # 63 integrated six-axis force launch file +│ ├── rm_63_display.launch.py # 63 launch file +│ ├── rm_65_6f_display.launch.py # 65 six-axis force launch file +│ ├── rm_65_6fb_display.launch.py # 65 integrated six-axis force launch file +│ ├── rm_65_display.launch.py # 65 launch file +│ ├── rm_75_6f_display.launch.py # 75 six-axis force launch file +│ ├── rm_75_6fb_display.launch.py # 75 integrated six-axis force launch file +│ ├── rm_75_display.launch.py # 75 launch file +│ ├── rm_eco65_6f_display.launch.py # eco65 six-axis force launch file +│ ├── rm_eco65_6fb_display.launch.py # eco65 integrated six-axis force launch file +│ ├── rm_eco65_display.launch.py # eco65 launch file +│ ├── rm_eco63_6fb_display.launch.py # eco63 integrated six-axis force launch file +│ ├── rm_eco63_display.launch.py # eco63 launch file +│ └── rm_gen72_display.launch.py # gen72 launch file +├── meshes # model file storage folder +│ ├── rm_63_arm #63 robotic arm model file storage folder +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6_6f.STL +│ │ ├── link6_6fb.STL +│ │ └── link6.STL +│ ├── rm_65_arm #65 robotic arm model file storage folder +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6_6f.STL +│ │ ├── link6_6fb.STL +│ │ └── link6.STL +│ ├── rm_75_arm #75 robotic arm model file storage folder +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6.STL +│ │ ├── link7_6f.STL +│ │ ├── link7_6fb.STL +│ │ └── link7.STL +│ └── rm_eco65_arm #eco65 robotic arm model file storage folder +│ │ ├── baselink.STL +│ │ ├── Link1.STL +│ │ ├── Link2.STL +│ │ ├── Link3.STL +│ │ ├── Link4.STL +│ │ ├── Link5.STL +│ │ ├── Link6_6f.STL +│ │ ├── Link6_6fb.STL +│ │ └── Link6.STL +│ └── rm_eco63_arm #eco63 robotic arm model file storage folder +│ │ ├── baselink.STL +│ │ ├── Link1.STL +│ │ ├── Link2.STL +│ │ ├── Link3.STL +│ │ ├── Link4.STL +│ │ ├── Link5.STL +│ │ ├── Link6_6fb.STL +│ │ └── Link6.STL +│ └── rm_gen72_arm #gen72 robotic arm model file storage folder +│ ├── base_link.STL +│ ├── Link1.STL +│ ├── Link2.STL +│ ├── Link3.STL +│ ├── Link4.STL +│ ├── Link5.STL +│ ├── Link6.STL +│ └── Link7.STL +├── package.xml +├── README_CN.md +├── README.md +├── rviz #rviz2 configuration file storage folder +│ ├── rm_63.rviz +│ ├── rm_65.rviz +│ ├── rm_75.rviz +│ └── rm_eco65.rviz +│ └── rm_eco63.rviz +│ └── rm_gen72.rviz +├── textures +└── urdf + ├── display_arm.rviz + ├── rm_65_6f.urdf #65 six-axis force urdf description file + ├── rm_65_6fb.urdf #65 integrated six-axis force urdf description file + ├── rm_65_description.csv + ├── rm_65_gazebo.urdf #65 gazebo simulation urdf description file + ├── rm_65_gazebo.urdf.xacro #65 gazebo simulation xacro description file + ├── rm_65.urdf #65 urdf description file + ├── rm_65.urdf.xacro #65 xacro description file + ├── rm_75_6f.urdf #75 six-axis force urdf description file + ├── rm_75_6fb.urdf #75 integrated six-axis force urdf description file + ├── rm_75_description.csv + ├── rm_75_gazebo.urdf #75 gazebo simulation urdf description file + ├── rm_75_gazebo.urdf.xacro #75 gazebo simulation xacro description file + ├── rm_75.urdf #75 urdf description file + ├── rm_75.urdf.xacro #75 xacro description file + ├── rm_eco65_6f.urdf #eco65 six-axis force urdf description file + ├── rm_eco65_6fb.urdf #eco65 integrated six-axis force urdf description file + ├── rm_eco65.csv + ├── rm_eco65_gazebo.urdf #eco65 gazebo simulation urdf description file + ├── rm_eco65_gazebo.urdf.xacro #eco65 gazebo simulation xacro description file + ├── rm_eco65.urdf #eco65 urdf description file + ├── rm_eco65.urdf.xacro #eco65 xacro description file + ├── rm_eco63_6fb.urdf #eco63 integrated six-axis force urdf description file + ├── rm_eco63.csv + ├── rm_eco63_gazebo.urdf #eco63 gazebo simulation urdf description file + ├── rm_eco63_gazebo.urdf.xacro #eco63 gazebo simulation xacro description file + ├── rm_eco63.urdf #eco63 urdf description file + ├── rm_eco63.urdf.xacro #eco63 xacro description file + ├── rm_gen72.csv + ├── rm_gen72_gazebo.urdf #gen72 gazebo simulation urdf description file + ├── rm_gen72.urdf #gen72 urdf description file + ├── rml_63_6f.urdf #63 six-axis force urdf description file + ├── rml_63_6fb.urdf #63 integrated six-axis force urdf description file + ├── rml_63_description.csv + ├── rml_63_gazebo.urdf #63 gazebo simulation urdf description file + ├── rml_63_gazebo.urdf.xacro #63 gazebo simulation xacro description file + ├── rml_63.urdf #63 urdf description file + └── rml_63.urdf.xacro #63 xacro description file +``` +## rm_description_Topic_Description +The following is the topic description of the package. +``` + Subscribers: + /joint_states: sensor_msgs/msg/JointState + /parameter_events: rcl_interfaces/msg/ParameterEvent + Publishers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /robot_description: std_msgs/msg/String + /rosout: rcl_interfaces/msg/Log + /tf: tf2_msgs/msg/TFMessage + /tf_static: tf2_msgs/msg/TFMessage + Service Servers: + /robot_state_publisher/describe_parameters: rcl_interfaces/srv/DescribeParameters + /robot_state_publisher/get_parameter_types: rcl_interfaces/srv/GetParameterTypes + /robot_state_publisher/get_parameters: rcl_interfaces/srv/GetParameters + /robot_state_publisher/list_parameters: rcl_interfaces/srv/ListParameters + /robot_state_publisher/set_parameters: rcl_interfaces/srv/SetParameters + /robot_state_publisher/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically + Service Clients: + + Action Servers: + + Action Clients: +``` +We mainly focus on the following topics. +Subscribers: represents the topics it subscribes to, where /joint_states represents the current state of the robotic arm, which is published by our rm_driver package when running so that the model in rviz moves according to the actual state of the robotic arm. +Publishers: represents the topics it currently publishes, where the most important published topics are /tf and /tf_static, which describe the coordinate transformation relationship between the joints of the robotic arm, namely TF transformation. +There are relatively few remaining topics and service use scenarios and you can learn by yourself. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README_CN.md new file mode 100644 index 0000000..2d5d717 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/README_CN.md @@ -0,0 +1,232 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_description/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_description/README.md) + +
+ +
+ +# 睿尔曼机器人rm_description使用说明书V1.4 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-3 |修订(添加GEN72适配文件) | +|V1.2 |2024-9-11 |修订(添加ECO63适配文件) | +|V1.3 |2024-12-25 |修订(添加了63、65、75、ECO65的六维力适配文件,以及63、65、75、ECO63、ECO65的一体化六维力适配文件) | +|V1.4 |2025-4-7 |修订(添加了GEN72_II适配文件) | + +
+ +## 目录 +* 1.[rm_description功能包说明](#rm_description功能包说明) +* 2.[rm_description功能包使用](#rm_description功能包使用) +* 3.[rm_description功能包架构说明](#rm_description功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4.[rm_description话题说明](#rm_description话题说明) + +## rm_description功能包说明 +rm_description功能包为显示机器人模型和TF变换的功能包,通过该功能包,我们可以实现电脑中的虚拟机械臂与现实中的实际机械臂的联动的效果,在之后的moveit2的控制中我们也需要该功能包的支持。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用 +## rm_description功能包使用 +首先配置好环境完成连接后我们可以通过以下命令直接启动节点,运行rm_description功能包。 +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__display.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65, eco63、75、gen72。 +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6f_display.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6fb_display.launch.py +``` +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_description rm_65_display.launch.py +``` +节点启动成功后,将显示以下画面。 +![image](doc/rm_description2.png) +之后我们还需要启动rm_driver节点。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +启动成功后我们就可以在rviz2中,查看机械臂状态了,运行如下命令启动rviz2。 +``` +rm@rm-desktop:~$ rviz2 +``` +通过如下配置打开机器人模型。 +![image](doc/rm_description3.png) +在rm_description功能包的rviz文件夹下找到对应的配置文件。 +![image](doc/rm_description4.png) +加载后就可以在rviz2的界面中看到当前的机械臂状态了。 +![image](doc/rm_description1.png) +## rm_description功能包架构说明 +## 功能包文件总览 +当前rm_description功能包的文件构成如下。 +``` +├── CMakeLists.txt #编译规则文件 +├── launch +│ ├── rm_63_6f_display.launch.py #63六维力启动文件 +│ ├── rm_63_6fb_display.launch.py #63一体化六维力启动文件 +│ ├── rm_63_display.launch.py #63启动文件 +│ ├── rm_65_6f_display.launch.py #65六维力启动文件 +│ ├── rm_65_6fb_display.launch.py #65一体化六维力启动文件 +│ ├── rm_65_display.launch.py #65启动文件 +│ ├── rm_75_6f_display.launch.py #75六维力启动文件 +│ ├── rm_75_6fb_display.launch.py #75一体化六维力启动文件 +│ ├── rm_75_display.launch.py #75启动文件 +│ ├── rm_eco63_6fb_display.launch.py #eco63一体化六维力启动文件 +│ ├── rm_eco63_display.launch.py #eco63启动文件 +│ ├── rm_eco65_6f_display.launch.py #eco65六维力启动文件 +│ ├── rm_eco65_6fb_display.launch.py #eco65一体化六维力启动文件 +│ ├── rm_eco65_display.launch.py #eco65启动文件 +│ └── rm_gen72_display.launch.py #gen72启动文件 +├── meshes #模型文件存放文件夹 +│ ├── rm_63_arm #63机械臂模型文件存放文件夹 +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6_6f.STL +│ │ ├── link6_6fb.STL +│ │ └── link6.STL +│ ├── rm_65_arm #65机械臂模型文件存放文件夹 +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6_6f.STL +│ │ ├── link6_6fb.STL +│ │ └── link6.STL +│ ├── rm_75_arm #75机械臂模型文件存放文件夹 +│ │ ├── base_link.STL +│ │ ├── link1.STL +│ │ ├── link2.STL +│ │ ├── link3.STL +│ │ ├── link4.STL +│ │ ├── link5.STL +│ │ ├── link6.STL +│ │ ├── link7_6f.STL +│ │ ├── link7_6fb.STL +│ │ └── link7.STL +│ └── rm_eco65_arm #eco65机械臂模型文件存放文件夹 +│ │ ├── baselink.STL +│ │ ├── Link1.STL +│ │ ├── Link2.STL +│ │ ├── Link3.STL +│ │ ├── Link4.STL +│ │ ├── Link5.STL +│ │ ├── Link6_6f.STL +│ │ ├── Link6_6fb.STL +│ │ └── Link6.STL +│ └── rm_eco63_arm #eco63机械臂模型文件存放文件夹 +│ │ ├── baselink.STL +│ │ ├── Link1.STL +│ │ ├── Link2.STL +│ │ ├── Link3.STL +│ │ ├── Link4.STL +│ │ ├── Link5.STL +│ │ ├── Link6_6fb.STL +│ │ └── Link6.STL +│ └── rm_gen72_arm #gen72机械臂模型文件存放文件夹 +│ ├── base_link.STL +│ ├── Link1.STL +│ ├── Link2.STL +│ ├── Link3.STL +│ ├── Link4.STL +│ ├── Link5.STL +│ ├── Link6.STL +│ └── Link7.STL +├── package.xml +├── rviz #rviz2配置文件存放文件夹 +│ ├── rm_63.rviz +│ ├── rm_65.rviz +│ ├── rm_75.rviz +│ ├── rm_eco65.rviz +│ ├── rm_eco63.rviz +│ └── rm_gen72.rviz +├── textures +└── urdf + ├── display_arm.rviz + ├── rm_65_6f.urdf #65 六维力urdf描述文件 + ├── rm_65_6fb.urdf #65 一体化六维力urdf描述文件 + ├── rm_65_description.csv + ├── rm_65_gazebo.urdf #65 gazebo仿真urdf描述文件 + ├── rm_65_gazebo.urdf.xacro #65 gazebo仿真xacro描述文件 + ├── rm_65.urdf #65 urdf描述文件 + ├── rm_65.urdf.xacro #65 xacro描述文件 + ├── rm_75_6f.urdf #75 六维力urdf描述文件 + ├── rm_75_6fb.urdf #75 一体化六维力urdf描述文件 + ├── rm_75_description.csv + ├── rm_75_gazebo.urdf #75 gazebo仿真urdf描述文件 + ├── rm_75_gazebo.urdf.xacro #75 gazebo仿真xacro描述文件 + ├── rm_75.urdf #75 urdf描述文件 + ├── rm_75.urdf.xacro #75 xacro描述文件 + ├── rm_eco65_6f.urdf #eco65 六维力urdf描述文件 + ├── rm_eco65_6fb.urdf #eco65 一体化六维力urdf描述文件 + ├── rm_eco65.csv + ├── rm_eco65_gazebo.urdf #eco65 gazebo仿真urdf描述文件 + ├── rm_eco65_gazebo.urdf.xacro #eco65 gazebo仿真xacro描述文件 + ├── rm_eco65.urdf #eco65 urdf描述文件 + ├── rm_eco65.urdf.xacro #eco65 xacro描述文件 + ├── rm_eco63_6fb.urdf #eco63 一体化六维力urdf描述文件 + ├── rm_eco63_gazebo.urdf #eco63 gazebo仿真urdf描述文件 + ├── rm_eco63_gazebo.urdf.xacro #eco63 gazebo仿真xacro描述文件 + ├── rm_eco63.csv + ├── rm_eco63.urdf #eco63 urdf描述文件 + ├── rm_eco63.urdf.xacro #eco63 xacro描述文件 + ├── rm_gen72.csv + ├── rm_gen72_gazebo.urdf #gen72gazebo仿真urdf描述文件 + ├── rm_gen72.urdf #gen72 urdf描述文件 + ├── rml_63_6f.urdf #63 六维力urdf描述文件 + ├── rml_63_6fb.urdf #63 一体化六维力urdf描述文件 + ├── rml_63_description.csv + ├── rml_63_gazebo.urdf #63 gazebo仿真urdf描述文件 + ├── rml_63_gazebo.urdf.xacro #63 gazebo仿真xacro描述文件 + ├── rml_63.urdf #63 urdf描述文件 + └── rml_63.urdf.xacro #63 xacro描述文件 +``` +## rm_description话题说明 +如下为该功能包的话题说明。 +``` + Subscribers: + /joint_states: sensor_msgs/msg/JointState + /parameter_events: rcl_interfaces/msg/ParameterEvent + Publishers: + /parameter_events: rcl_interfaces/msg/ParameterEvent + /robot_description: std_msgs/msg/String + /rosout: rcl_interfaces/msg/Log + /tf: tf2_msgs/msg/TFMessage + /tf_static: tf2_msgs/msg/TFMessage + Service Servers: + /robot_state_publisher/describe_parameters: rcl_interfaces/srv/DescribeParameters + /robot_state_publisher/get_parameter_types: rcl_interfaces/srv/GetParameterTypes + /robot_state_publisher/get_parameters: rcl_interfaces/srv/GetParameters + /robot_state_publisher/list_parameters: rcl_interfaces/srv/ListParameters + /robot_state_publisher/set_parameters: rcl_interfaces/srv/SetParameters + /robot_state_publisher/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically + Service Clients: + + Action Servers: + + Action Clients: +``` +我们主要关注以下几个话题。 +Subscribers:代表其订阅的话题,其中的/joint_states代表机械臂当前的状态,我们的rm_driver功能包运行时会发布该话题,这样rviz中的模型就会根据实际的机械臂状态进行运动。 +Publishers:代表其当前发布的话题,其最主要发布的话题为/tf和/tf_static,这两个话题描述了机械臂关节与关节之间的坐标变换关系,也就是TF变换。 +剩余话题和服务使用场景较少,大家可自行了解。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rm_65_description.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rm_65_description.yaml new file mode 100644 index 0000000..333c13a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rm_65_description.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6', ] diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rml_63_description.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rml_63_description.yaml new file mode 100644 index 0000000..333c13a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/config/joint_names_rml_63_description.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6', ] diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description1.png new file mode 100644 index 0000000..6641a04 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description2.png new file mode 100644 index 0000000..b1720a7 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description3.png new file mode 100644 index 0000000..07c0db8 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description3.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description4.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description4.png new file mode 100644 index 0000000..5d63fc5 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/doc/rm_description4.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6f_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6f_display.launch.py new file mode 100644 index 0000000..329fe03 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6f_display.launch.py @@ -0,0 +1,33 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6f', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rml_63.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file,' ','link6_type:=',LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6fb_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6fb_display.launch.py new file mode 100644 index 0000000..c9b861e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_6fb_display.launch.py @@ -0,0 +1,33 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6fb', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rml_63.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file,' ','link6_type:=',LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_display.launch.py new file mode 100644 index 0000000..ee73131 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_63_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rml_63.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6f_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6f_display.launch.py new file mode 100644 index 0000000..28f9757 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6f_display.launch.py @@ -0,0 +1,34 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6f', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_65.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file, ' ', 'link6_type:=', LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6fb_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6fb_display.launch.py new file mode 100644 index 0000000..e67d732 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_6fb_display.launch.py @@ -0,0 +1,34 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6fb', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_65.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file, ' ', 'link6_type:=', LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_display.launch.py new file mode 100644 index 0000000..2f4dd6c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_65_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_65.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6f_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6f_display.launch.py new file mode 100644 index 0000000..9609ff7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6f_display.launch.py @@ -0,0 +1,31 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + # 声明参数 link7_type + declare_link7_type_arg = DeclareLaunchArgument( + 'link7_type', + default_value='Link7_6f', + description='Type of link7' + ) + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_75.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file, ' ','link7_type:=', LaunchConfiguration('link7_type')]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6fb_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6fb_display.launch.py new file mode 100644 index 0000000..7f28f51 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_6fb_display.launch.py @@ -0,0 +1,32 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + # 声明参数 link7_type + declare_link7_type_arg = DeclareLaunchArgument( + 'link7_type', + default_value='Link7_6fb', + description='Type of link7' + ) + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_75.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file, ' ','link7_type:=', LaunchConfiguration('link7_type')]) + + return LaunchDescription([ + declare_link7_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_display.launch.py new file mode 100644 index 0000000..f93fdcf --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_75_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_75.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_6fb_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_6fb_display.launch.py new file mode 100644 index 0000000..0c64e01 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_6fb_display.launch.py @@ -0,0 +1,32 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6fb', + description='Type of link6' + ) + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_eco63.urdf.xacro') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file,' ','link6_type:=',LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ), + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_display.launch.py new file mode 100644 index 0000000..21a43a9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco63_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_eco63.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ), + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6f_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6f_display.launch.py new file mode 100644 index 0000000..6ebf5fd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6f_display.launch.py @@ -0,0 +1,34 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6f', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_eco65.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file,' ','link6_type:=',LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ), + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6fb_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6fb_display.launch.py new file mode 100644 index 0000000..ace64e3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_6fb_display.launch.py @@ -0,0 +1,34 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + # 声明参数 link6_type + declare_link6_type_arg = DeclareLaunchArgument( + 'link6_type', + default_value='Link6_6fb', + description='Type of link6' + ) + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_eco65.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file,' ','link6_type:=',LaunchConfiguration('link6_type')]) + + return LaunchDescription([ + declare_link6_type_arg, + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ), + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_display.launch.py new file mode 100644 index 0000000..1d37493 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_eco65_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_eco65.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ), + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_II_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_II_display.launch.py new file mode 100644 index 0000000..b15187c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_II_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_gen72_II.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_display.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_display.launch.py new file mode 100644 index 0000000..e281e9d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/launch/rm_gen72_display.launch.py @@ -0,0 +1,26 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, LaunchConfiguration + +import xacro + +def generate_launch_description(): + + realman_xacro_file = os.path.join(get_package_share_directory('rm_description'), 'urdf', + 'rm_gen72.urdf') + robot_description = Command( + [FindExecutable(name='xacro'), ' ', realman_xacro_file]) + + return LaunchDescription([ + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + respawn=True, + parameters=[{'robot_description': robot_description}], + output='screen' + ) + ]) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/base_link.STL new file mode 100644 index 0000000..7ef1778 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link1.STL new file mode 100644 index 0000000..a1e862d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link2.STL new file mode 100644 index 0000000..f165eb7 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link3.STL new file mode 100644 index 0000000..8e41cb9 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link4.STL new file mode 100644 index 0000000..dca6273 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link5.STL new file mode 100644 index 0000000..4dcd8f5 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6.STL new file mode 100644 index 0000000..6aaa544 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6f.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6f.STL new file mode 100644 index 0000000..cefc31d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6f.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6fb.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6fb.STL new file mode 100644 index 0000000..1d4adfe Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_63_arm/link6_6fb.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/base_link.STL new file mode 100644 index 0000000..0889070 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link1.STL new file mode 100644 index 0000000..9e488ed Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link2.STL new file mode 100644 index 0000000..7c40979 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link3.STL new file mode 100644 index 0000000..de9e6b6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link4.STL new file mode 100644 index 0000000..80ce2f4 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link5.STL new file mode 100644 index 0000000..d40ecc3 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6.STL new file mode 100644 index 0000000..b67bf2b Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6f.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6f.STL new file mode 100644 index 0000000..fea0fef Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6f.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6fb.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6fb.STL new file mode 100644 index 0000000..81ec5b6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_65_arm/link6_6fb.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/base_link.STL new file mode 100644 index 0000000..a1bb922 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link1.STL new file mode 100644 index 0000000..ae7a15d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link2.STL new file mode 100644 index 0000000..2b814d8 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link3.STL new file mode 100644 index 0000000..e6ac4af Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link4.STL new file mode 100644 index 0000000..aa955e5 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link5.STL new file mode 100644 index 0000000..36959b6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link6.STL new file mode 100644 index 0000000..4213c3c Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7.STL new file mode 100644 index 0000000..bf0f9c4 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6f.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6f.STL new file mode 100644 index 0000000..5a538a7 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6f.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6fb.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6fb.STL new file mode 100644 index 0000000..81ec5b6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_75_arm/link7_6fb.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link1.STL new file mode 100644 index 0000000..d6d2d46 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link2.STL new file mode 100644 index 0000000..28f78fb Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link3.STL new file mode 100644 index 0000000..c683069 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link4.STL new file mode 100644 index 0000000..d96fdac Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link5.STL new file mode 100644 index 0000000..b9a1485 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link6.STL new file mode 100644 index 0000000..d030541 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/Link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/base_link.STL new file mode 100644 index 0000000..6648df3 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco62_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link1.STL new file mode 100644 index 0000000..5e37ba6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link2.STL new file mode 100644 index 0000000..0a31e83 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link3.STL new file mode 100644 index 0000000..49f3a3e Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link4.STL new file mode 100644 index 0000000..562e40d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link5.STL new file mode 100644 index 0000000..7273f8d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6.STL new file mode 100644 index 0000000..4688a18 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6_6fb.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6_6fb.STL new file mode 100644 index 0000000..d6702e2 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/Link6_6fb.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/base_link.STL new file mode 100644 index 0000000..dfa6f49 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco63_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link1.STL new file mode 100644 index 0000000..ea524c1 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link2.STL new file mode 100644 index 0000000..886d330 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link3.STL new file mode 100644 index 0000000..537be78 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link4.STL new file mode 100644 index 0000000..7766e32 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link5.STL new file mode 100644 index 0000000..d5d7f4f Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6.STL new file mode 100644 index 0000000..81411a4 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6f.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6f.STL new file mode 100644 index 0000000..635a877 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6f.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6fb.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6fb.STL new file mode 100644 index 0000000..1226476 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/Link6_6fb.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/baselink.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/baselink.STL new file mode 100644 index 0000000..f8ce87d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_eco65_arm/baselink.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link1.STL new file mode 100755 index 0000000..27b0410 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link2.STL new file mode 100755 index 0000000..4fda773 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link3.STL new file mode 100755 index 0000000..8978a22 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link4.STL new file mode 100755 index 0000000..b6fe7de Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link5.STL new file mode 100755 index 0000000..31aea67 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link6.STL new file mode 100755 index 0000000..c98124e Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link7.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link7.STL new file mode 100755 index 0000000..7a416c8 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/Link7.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/base_link.STL new file mode 100755 index 0000000..8094c53 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_II_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link1.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link1.STL new file mode 100644 index 0000000..7599aaf Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link1.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link2.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link2.STL new file mode 100644 index 0000000..86920b4 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link2.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link3.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link3.STL new file mode 100644 index 0000000..819d225 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link3.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link4.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link4.STL new file mode 100644 index 0000000..e95137d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link4.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link5.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link5.STL new file mode 100644 index 0000000..68dd8ae Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link5.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link6.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link6.STL new file mode 100644 index 0000000..435f076 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link6.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link7.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link7.STL new file mode 100755 index 0000000..efaff16 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/Link7.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/base_link.STL b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/base_link.STL new file mode 100644 index 0000000..ca4c704 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/meshes/rm_gen72_arm/base_link.STL differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/package.xml new file mode 100644 index 0000000..f6e5628 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/package.xml @@ -0,0 +1,18 @@ + + + + rm_description + 0.0.0 + TODO: Package description + ubuntu + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_63.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_63.rviz new file mode 100644 index 0000000..f3af3a5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_63.rviz @@ -0,0 +1,195 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.8979061841964722 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.08790659159421921 + Y: -0.1267784833908081 + Z: 0.25718244910240173 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3703983426094055 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.3753986358642578 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 503 + Y: 68 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_65.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_65.rviz new file mode 100644 index 0000000..4476148 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_65.rviz @@ -0,0 +1,200 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link7: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.8979061841964722 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.08790659159421921 + Y: -0.1267784833908081 + Z: 0.25718244910240173 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3703983426094055 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.3753986358642578 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 503 + Y: 68 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_75.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_75.rviz new file mode 100644 index 0000000..187762f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_75.rviz @@ -0,0 +1,200 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link7: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.8979061841964722 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.10530813783407211 + Y: -0.1396769881248474 + Z: 0.6537870764732361 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -0.09460150450468063 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.06540007144212723 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 298 + Y: 105 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco63.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco63.rviz new file mode 100644 index 0000000..c527ae4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco63.rviz @@ -0,0 +1,195 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 245 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0772488117218018 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.1823197305202484 + Y: 0.011119896546006203 + Z: 0.3867513835430145 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3803982138633728 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.265397787094116 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 542 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000180fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000180000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000180fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000180000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f0000018000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 74 + Y: 331 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco65.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco65.rviz new file mode 100644 index 0000000..c47bc99 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_eco65.rviz @@ -0,0 +1,195 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + baselink: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: baselink + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.8979061841964722 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.08790659159421921 + Y: -0.1267784833908081 + Z: 0.25718244910240173 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.6653980612754822 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.08039874583482742 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 503 + Y: 68 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_gen72.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_gen72.rviz new file mode 100644 index 0000000..d79bd48 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/rviz/rm_gen72.rviz @@ -0,0 +1,200 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 245 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link7: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.4508087635040283 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.1102934181690216 + Y: -0.04993670433759689 + Z: 0.2724209129810333 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.34039831161499023 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.3003978729248047 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 542 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000180fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000180000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000180fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000180000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f0000018000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 248 + Y: 83 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/display_arm.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/display_arm.rviz new file mode 100644 index 0000000..f3af3a5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/display_arm.rviz @@ -0,0 +1,195 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.8979061841964722 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.08790659159421921 + Y: -0.1267784833908081 + Z: 0.25718244910240173 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3703983426094055 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.3753986358642578 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 503 + Y: 68 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf new file mode 100644 index 0000000..ea3999f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf.xacro new file mode 100644 index 0000000..36cab4d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65.urdf.xacro @@ -0,0 +1,542 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6f.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6f.urdf new file mode 100644 index 0000000..c0a983f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6f.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6fb.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6fb.urdf new file mode 100644 index 0000000..b3def01 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_6fb.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_description.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_description.csv new file mode 100644 index 0000000..3ff31b4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_description.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,-0.000433277303987328,-3.54664423471128E-05,0.0599427668933796,0,0,0,0.841070778135659,0.0017261110801622,2.52746264980217E-06,-3.67690303614961E-05,0.00170987405835604,1.67996364994424E-06,0.000904023422915791,0,0,0,0,0,0,package://rm_65_description/meshes/base_link.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/base_link.STL,,连杆1-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +link1,1.2226305431569E-08,0.0211079974844683,-0.0251854220842269,0,0,0,0.593563443690403,0.00126614120341847,-1.294980943835E-08,-9.80120923066996E-09,0.00118168178300364,-0.00021121727444415,0.00056135241627747,0,0,0,0,0,0,package://rm_65_description/meshes/link1.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link1.STL,,连杆2-1,坐标系2,基准轴1,joint1,revolute,0,0,0.2405,0,0,0,base_link,0,0,-1,100,1,-3.14,3.14,,,,,,,, +link2,0.152256463426163,4.75383656106654E-07,-0.00620260383607792,0,0,0,0.864175046869043,0.00089150298478414,-2.23268489334765E-08,0.00156246461035015,0.00733754343083901,6.28110889329165E-09,0.00697869103915473,0,0,0,0,0,0,package://rm_65_description/meshes/link2.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link2.STL,,连杆3-1;连杆4-1,坐标系3,基准轴2,joint2,revolute,0,0,0,1.5708,-1.5708,0,link1,0,0,1,100,1,-2.268,2.268,,,,,,,, +link3,5.05312670989961E-06,-0.0595925663694732,0.010569069212336,0,0,0,0.289633681624654,0.00063737100450158,-7.05261293649751E-08,-3.86643272239426E-08,0.00015648388095025,-0.00014461035994916,0.000614178164773085,0,0,0,0,0,0,package://rm_65_description/meshes/link3.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link3.STL,,连杆5-1,坐标系4,基准轴3,joint3,revolute,0.256,0,0,0,0,1.5708,link2,0,0,1,100,1,-2.355,2.355,,,,,,,, +link4,1.15516617405898E-06,-0.0180424468598241,-0.0215394748352687,0,0,0,0.239419768320061,0.000285938919722783,3.07101359163101E-09,-2.21994118981953E-09,0.000262727540304212,4.4236583260078E-05,0.000119888082791859,0,0,0,0,0,0,package://rm_65_description/meshes/link4.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link4.STL,,连杆6-1,坐标系5,基准轴4,joint4,revolute,0,-0.21,0,1.5708,0,0,link3,0,0,1,100,1,-3.14,3.14,,,,,,,, +link5,3.19794786262152E-06,-0.0593808368101458,0.00736804250989326,0,0,0,0.218799761431678,0.000350540363914072,-3.41781619975602E-08,-1.77056457224373E-08,0.000104927867487581,-7.82431228461971E-05,0.000334482418423629,0,0,0,0,0,0,package://rm_65_description/meshes/link5.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link5.STL,,连杆7-1,坐标系6,基准轴5,joint5,revolute,0,0,0,-1.5708,0,0,link4,0,0,1,100,1,-2.233,2.233,,,,,,,, +link6,0.000714234511756999,-0.000396718732824521,-0.0126723660946126,0,0,0,0.0649018034311231,2.02766547502765E-05,-1.32505200276849E-06,-2.5845091522508E-08,1.87986725225022E-05,3.39471452125439E-09,3.17885459163081E-05,0,0,0,0,0,0,package://rm_65_description/meshes/link6.STL,1,1,1,1,0,0,0,0,0,0,package://rm_65_description/meshes/link6.STL,,末端法兰件-1,坐标系7,基准轴6,joint6,continuous,0,-0.144,0,1.5708,0,0,link5,0,0,1,100,1,-6.28,6.28,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf new file mode 100644 index 0000000..11f0a15 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf @@ -0,0 +1,448 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf.xacro new file mode 100644 index 0000000..b76aae6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_65_gazebo.urdf.xacro @@ -0,0 +1,590 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf new file mode 100644 index 0000000..946900b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf.xacro new file mode 100644 index 0000000..c2e11dc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75.urdf.xacro @@ -0,0 +1,575 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6f.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6f.urdf new file mode 100644 index 0000000..25a4c0f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6f.urdf @@ -0,0 +1,453 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6fb.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6fb.urdf new file mode 100644 index 0000000..bbe7ff8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_6fb.urdf @@ -0,0 +1,453 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_description.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_description.csv new file mode 100644 index 0000000..bdb6a04 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_description.csv @@ -0,0 +1,9 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,0.000433268851866144,3.54527840972405E-05,0.0599427623574736,0,0,0,0.841071174772543,0.00172611149818605,2.52724703312125E-06,3.67689528877993E-05,0.00170987425756066,-1.68009023667311E-06,0.000904023916742301,0,0,0,0,0,0,package://rm_75_description/meshes/base_link.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/base_link.STL,,连杆1-1,坐标系1,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +Link1,0.0251854224372461,1.19160585601655E-08,-0.021107996993288,0,0,0,0.593563458735581,0.000561352422092522,9.8019294192418E-09,-0.000211217278563478,0.00126614121202124,1.29510293158304E-08,0.0011816817861243,0,0,0,0,0,0,package://rm_75_description/meshes/link1.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link1.STL,,连杆2-1,坐标系2,基准轴1,joint1,revolute,0,0,0.2405,1.5708,1.5708,0,base_link,1,0,0,100,1,-3.14,3.14,,,,,,,, +Link2,2.72859133252335E-07,0.011077753037361,0.0761295106490881,0,0,0,0.432849770310974,0.00125838173873093,5.63146579602116E-09,1.33486683063366E-09,0.00122245448121472,0.000279003475762058,0.000317474184276672,0,0,0,0,0,0,package://rm_75_description/meshes/link2.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link2.STL,,连杆3-1,坐标系3,基准轴2,joint2,revolute,0,0,0,1.5708,0,-1.5708,Link1,0,1,0,100,1,-2.268,2.268,,,,,,,, +Link3,6.84676164566044E-07,0.0273475408308154,-0.0235440119707943,0,0,0,0.431325495678459,0.000794332771462568,1.03353218375171E-08,-2.32798826854953E-09,0.000315065343266245,-0.000142620540462618,0.000730371131605455,0,0,0,0,0,0,package://rm_75_description/meshes/link3.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link3.STL,,连杆4-1,坐标系4,基准轴3,joint3,revolute,0,0,0.256,-1.5708,0,0,Link2,0,1,0,100,1,-3.14,3.14,,,,,,,, +Link4,5.05312670298932E-06,0.0105690692118619,0.0595925663703773,0,0,0,0.289633681619295,0.000637371004484591,-3.86643270900744E-08,7.05261290886955E-08,0.000614178164759844,0.000144610359942128,0.000156483880946498,0,0,0,0,0,0,package://rm_75_description/meshes/link4.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link4.STL,,连杆5-1,坐标系5,基准轴4,joint4,revolute,0,0,0,1.5708,0,0,Link3,0,1,0,100,1,-2.355,2.355,,,,,,,, +Link5,1.1551661767744E-06,0.0215394748352686,-0.0180424468598241,0,0,0,0.239419768320061,0.000285938919722783,2.21994116852616E-09,3.07101358617598E-09,0.00011988808279186,-4.4236583260078E-05,0.000262727540304212,0,0,0,0,0,0,package://rm_75_description/meshes/link5.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link5.STL,,连杆6-1,坐标系6,基准轴5,joint5,revolute,0,0,0.21,-1.5708,0,0,Link4,0,-1,0,100,1,-3.14,3.14,,,,,,,, +Link6,3.19794787018954E-06,0.00736804250989373,0.0593808368101291,0,0,0,0.218799761431682,0.000350540363914436,-1.7705645712277E-08,3.41781620449632E-08,0.000334482418423991,7.82431228462317E-05,0.000104927867487584,0,0,0,0,0,0,package://rm_75_description/meshes/link6.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link6.STL,,连杆7-1,坐标系7,基准轴6,joint6,revolute,0,0,0,1.5708,0,0,Link5,0,1,0,100,1,-2.233,2.233,,,,,,,, +Link7,0.000714238382876259,-0.000396711987952758,-0.0126723660946126,0,0,0,0.0649018034311231,2.02766547502765E-05,-1.32505200276848E-06,-2.58450915224912E-08,1.87986725225022E-05,3.39471452123283E-09,3.17885459163081E-05,0,0,0,0,0,0,package://rm_75_description/meshes/link7.STL,1,1,1,1,0,0,0,0,0,0,package://rm_75_description/meshes/link7.STL,,末端法兰件-1,坐标系8,基准轴7,joint7,continuous,0,0,0.144,0,0,0,Link6,0,0,1,100,1,-6.28,6.28,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf new file mode 100644 index 0000000..1524367 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf.xacro new file mode 100644 index 0000000..001d3c9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_75_gazebo.urdf.xacro @@ -0,0 +1,575 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.csv new file mode 100644 index 0000000..bd98496 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,0.00039308,-8.9311E-05,0.050351,0,0,0,0.70684,0.001114,3.3208E-06,-2.5536E-05,0.0011138,1.4832E-06,0.00075793,0,0,0,0,0,0,package://ECO63URDF3/meshes/base_link.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/base_link.STL,,111-1,baselink,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +Link1,-0.032161,-0.002588,-0.0071715,0,0,0,0.7339,0.00065754,-0.00012029,0.00016575,0.0018838,1.5479E-05,0.0017351,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link1.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link1.STL,,222-1,link1,line1,joint1,revolute,0,0,0.1625,0,0,0,base_link,0,0,1,0,0,-3.1,3.1,,,,,,,, +Link2,0.19469,6.6139E-07,-0.070874,0,0,0,1.9492,0.001497,1.4887E-07,-0.00045122,0.040644,1.3757E-08,0.040997,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link2.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link2.STL,,333-1,link2,line2,joint2,revolute,-0.086,0,0,1.5708,-1.5708,0,Link1,0,0,1,0,0,-3.1,3.1,,,,,,,, +Link3,0.1718,6.3595E-07,0.026691,0,0,0,1.4553,0.00094612,-1.1572E-07,-0.0008623,0.025574,-2.426E-08,0.025646,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link3.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link3.STL,,444-1,link3,line3,joint3,revolute,0.41,0,0,0,0,0,Link2,0,0,1,0,0,-2.95,2.76,,,,,,,, +Link4,6.6185E-07,-0.0098798,0.013446,0,0,0,0.27261,0.00023835,2.6006E-09,-2.5717E-09,0.00019072,-4.0013E-05,0.0001713,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link4.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link4.STL,,555-1,link4,line4,joint4,revolute,0.38,0,-0.0589,0,0,1.5708,Link3,0,0,1,0,0,-2.44,2.44,,,,,,,, +Link5,-3.0395E-07,7.9935E-05,-0.014767,0,0,0,0.31149,0.00030885,-5.8024E-09,3.5085E-09,0.00024407,-2.2834E-06,0.0002027,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link5.STL,0.86667,0.86667,0.8902,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link5.STL,,666-1,link5,line5,joint5,revolute,0,-0.11,0,1.5708,0,0,Link4,0,0,1,0,0,-3.14,3.14,,,,,,,, +Link6,0.00065547,-0.00036962,-0.015297,0,0,0,0.080797,2.4449E-05,-1.2142E-06,-1.0223E-07,2.3012E-05,6.5765E-08,3.661E-05,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link6.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://ECO63URDF3/meshes/Link6.STL,,000-1,link6,line6,joint6,revolute,0,0.079501,0,-1.5708,0,0,Link5,0,0,1,0,0,-6.28,6.28,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf new file mode 100644 index 0000000..ceb8c9f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf.xacro new file mode 100644 index 0000000..0fe8b24 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63.urdf.xacro @@ -0,0 +1,457 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_6fb.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_6fb.urdf new file mode 100644 index 0000000..9c80e67 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_6fb.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf new file mode 100644 index 0000000..7f4aee3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf.xacro new file mode 100644 index 0000000..24cedfe --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco63_gazebo.urdf.xacro @@ -0,0 +1,457 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.csv new file mode 100644 index 0000000..8131f80 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +baselink,0.00059982,-9.2932E-05,0.043301,0,0,0,0.61127,0.00080212,3.0281E-06,-2.8747E-05,0.00080502,1.9749E-06,0.00066167,0,0,0,0,0,0,package://eco65/meshes/baselink.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/baselink.STL,,1-1,baselink,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +Link1,-0.022858,-2.0784E-06,-0.013658,0,0,0,0.74247,0.00081398,-1.9024E-05,0.00022746,0.001848,2.0444E-06,0.0015286,0,0,0,0,0,0,package://eco65/meshes/Link1.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/Link1.STL,,2-1,Link1,axis1,joint1,revolute,0,0,0.1625,0,0,0,baselink,0,0,1,100,1,-3.14,3.14,,,,,,,, +Link2,-1.6049E-06,0.10336,0.067332,0,0,0,1.3502,0.012821,-7.2979E-08,1.1499E-08,0.0011237,-0.00033755,0.012933,0,0,0,0,0,0,package://eco65/meshes/Link2.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/Link2.STL,,3-1,Link2,axis2,joint2,revolute,-0.086,0,0,1.5708,0,0,Link1,0,0,1,100,1,-3.14,3.14,,,,,,,, +Link3,0.10374,7.0495E-07,0.018599,0,0,0,1.0422,0.00084115,-2.2514E-08,-0.00068613,0.0094046,-3.3287E-09,0.0092482,0,0,0,0,0,0,package://eco65/meshes/Link3.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/Link3.STL,,4-1,Link3,axis3,joint3,revolute,0,0.26,0,3.1416,0,1.5708,Link2,0,0,1,100,1,-2.79,2.53,,,,,,,, +Link4,-0.0069819,-0.016328,0.0067416,0,0,0,0.27383,0,0,0,0,0,0,0,0,0,0,0,0,package://eco65/meshes/Link4.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/Link4.STL,,5-1,Link4,axis4,joint4,revolute,0.24,0,-0.05888,0,0,1.5708,Link3,0,0,1,100,1,-2.44,2.44,,,,,,,, +Link5,-0.00040425,0.0066328,-0.012475,0,0,0,0.27794,0.00024751,-5.6849E-09,5.4838E-10,0.00017648,-2.8552E-05,0.00019295,0,0,0,0,0,0,package://eco65/meshes/Link5.STL,0.29804,0.28627,0.28235,1,0,0,0,0,0,0,package://eco65/meshes/Link5.STL,,6-1,Link5,axis5,joint5,revolute,0.00040486,-0.10983,0,1.5708,0,0,Link4,0,0,1,100,1,-3.14,3.14,,,,,,,, +Link6,0.00095587,-0.0013555,-0.010297,0,0,0,0.033025,1.2968E-05,-7.8692E-07,8.451E-08,1.1583E-05,-1.2002E-07,2.0405E-05,0,0,0,0,0,0,package://eco65/meshes/Link6.STL,1,1,0.9451,1,0,0,0,0,0,0,package://eco65/meshes/Link6.STL,,00-1,Link6,axis6,joint6,revolute,0,0.0795,0,-1.5708,0,0,Link5,0,0,1,100,1,-3.14,3.14,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf new file mode 100644 index 0000000..b436408 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf.xacro new file mode 100644 index 0000000..cad0045 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65.urdf.xacro @@ -0,0 +1,517 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6f.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6f.urdf new file mode 100644 index 0000000..2e8a79d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6f.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6fb.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6fb.urdf new file mode 100644 index 0000000..55a40f4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_6fb.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf new file mode 100644 index 0000000..b728428 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf @@ -0,0 +1,448 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf.xacro new file mode 100644 index 0000000..6a4e08c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_eco65_gazebo.urdf.xacro @@ -0,0 +1,589 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.csv new file mode 100644 index 0000000..52043c9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.csv @@ -0,0 +1,9 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,0.000608631599864255,0.000101410841221341,0.0500536423028978,0,0,0,0.725732279372221,0.00116526259312757,3.86984764040053E-06,3.61598634195252E-05,0.00114387939249157,-1.69159565748577E-06,0.000799620765266164,0,0,0,0,0,0,package://GEN72/meshes/base_link.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/base_link.STL,,00-1,坐标系0,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +Link1,3.54241616239891E-07,-6.04073277655109E-05,-0.0474562076947793,0,0,0,0.511231576042974,0.000959440501675413,-1.90967914521654E-09,-7.95751539476966E-09,0.00102039305288465,1.46570590325123E-06,0.000388714616194907,0,0,0,0,0,0,package://GEN72/meshes/Link1.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link1.STL,,01-3,坐标系1,基准轴1,joint1,revolute,0,0,0.218,0,0,0,base_link,0,0,1,25,3.141,-3.0014,3.0014,,,,,,,, +Link2,-7.13241796657627E-07,-0.0576246216952895,-3.88440270542586E-05,0,0,0,0.551907023014854,0.00142140348660694,-1.11761928109077E-08,1.36372804172861E-08,0.000525714272398651,1.30499471806307E-06,0.00127234961251408,0,0,0,0,0,0,package://GEN72/meshes/Link2.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link2.STL,,02-1,坐标系2,基准轴2,joint2,revolute,0,0,0,-1.5708,0,0,Link1,0,0,1,25,3.141,-1.8323,1.8323,,,,,,,, +Link3,0.00897441376214199,2.62633968732563E-05,-0.0738284702130494,0,0,0,0.774130450031732,0.00242102073961797,-6.22596416744622E-07,-0.000489521447339777,0.00248694314969316,-1.4854289556066E-06,0.00090099718971981,0,0,0,0,0,0,package://GEN72/meshes/Link3.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link3.STL,,03-1,坐标系3,基准轴3,joint3,revolute,0,-0.28,0,1.5708,0,0,Link2,0,0,1,25,3.141,-3.0014,3.0014,,,,,,,, +Link4,-0.0096243903445302,0.0352034287339325,0.000174576348464232,0,0,0,0.437130215853835,0.000866914153248166,0.000148761646913658,-7.42553547350131E-07,0.000267753002587664,2.6805826548563E-06,0.000952324298928138,0,0,0,0,0,0,package://GEN72/meshes/Link4.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link4.STL,,04-1,坐标系4,基准轴4,joint4,revolute,0.04,0,0,1.5708,0,0,Link3,0,0,1,25,3.141,-2.8792,0.9597,,,,,,,, +Link5,-4.79650184286029E-07,-3.84737693792612E-05,-0.0669554878200541,0,0,0,0.424276753764529,0.0011244489011316,7.56623220194193E-09,-1.71276249932631E-08,0.00103382374928123,8.2469441747875E-07,0.000274640088277484,0,0,0,0,0,0,package://GEN72/meshes/Link5.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link5.STL,,05-1,坐标系5,基准轴5,joint5,revolute,-0.019,0.2525,0,-1.5708,0,0,Link4,0,0,1,5,3.141,-3.0014,3.0014,,,,,,,, +Link6,0.00184221691932426,0.0379763265035087,-9.21090904324274E-05,0,0,0,0.302793039332829,0.00014011480503376,-3.00204828273403E-06,-4.58155498967514E-10,0.000132631402640971,7.01344540252765E-10,0.000155721320872423,0,0,0,0,0,0,package://GEN72/meshes/Link6.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link6.STL,,06-1,坐标系6,基准轴6,joint6,revolute,0,0,0,1.5708,0,0,Link5,0,0,1,5,3.141,-1.707,1.783,,,,,,,, +Link7,0.000199885014846801,0.0211000079719058,-4.90848725240361E-08,0,0,0,0.127401822079286,4.95156474993269E-05,3.10143792228514E-12,2.55814128583062E-10,6.12184422048225E-05,-1.37181281244006E-11,4.95166727643872E-05,0,0,0,0,0,0,package://GEN72/meshes/Link7.STL,1,1,1,1,0,0,0,0,0,0,package://GEN72/meshes/Link7.STL,,07-1,坐标系7,基准轴7,joint7,revolute,0.0742,0.067,0,0,0,1.5708,Link6,0,1,0,5,3.141,-3.0014,3.0014,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.urdf new file mode 100644 index 0000000..e0e20f1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II.urdf new file mode 100644 index 0000000..489f7be --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II_gazebo.urdf new file mode 100644 index 0000000..b12a564 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_II_gazebo.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_gazebo.urdf new file mode 100644 index 0000000..d6ae7c8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rm_gen72_gazebo.urdf @@ -0,0 +1,450 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf new file mode 100644 index 0000000..96c636d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf.xacro new file mode 100644 index 0000000..21529e9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63.urdf.xacro @@ -0,0 +1,518 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6f.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6f.urdf new file mode 100644 index 0000000..8244f7c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6f.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb.urdf new file mode 100644 index 0000000..5057148 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb_description.urdf.xacro new file mode 100644 index 0000000..f963671 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_6fb_description.urdf.xacro @@ -0,0 +1,553 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + 1 + + + + + + + + + + + + + + + /arm + gazebo_ros_control/DefaultRobotHWSim + true + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_description.csv b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_description.csv new file mode 100644 index 0000000..40917da --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_description.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,0.0014231,-0.00010178,0.050147,0,0,0,0.66171,0.00099443,3.282E-06,-9.9964E-06,0.0010144,1.2811E-06,0.00067929,0,0,0,0,0,0,package://rml_63_description/meshes/base_link.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/base_link.STL,,63连杆1-1,base_link,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +link1,-0.043281,-0.0072256,-0.012694,0,0,0,0.89496,0.0010156,-0.00026764,0.00045014,0.0024107,6.0996E-05,0.0022755,0,0,0,0,0,0,package://rml_63_description/meshes/link1.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link1.STL,,63连杆2-1,link_1,axis_1,joint1,revolute,0,0,0.172,0,0,0,base_link,0,0,1,100,1,-3.106,3.106,,,,,,,, +link2,0.17388,3.639E-07,-0.089966,0,0,0,1.5679,0.0010615,-7.3371E-08,-0.00025488,0.03035,-1.6148E-08,0.030485,0,0,0,0,0,0,package://rml_63_description/meshes/link2.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link2.STL,,63连杆3-1,link_2,axis_2,joint2,revolute,-0.086,0,0,1.5708,-1.5708,0,link1,0,0,1,100,1,-3.106,3.106,,,,,,,, +link3,0.035968,-0.020568,-0.0048526,0,0,0,0.67539,0.00091144,0.00043238,-0.0001205,0.0012128,6.6376E-05,0.0015231,0,0,0,0,0,0,package://rml_63_description/meshes/link3.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link3.STL,,63连杆4-1,link_3,axis_3,joint3,revolute,0.38,0,-0.00030011,0,0,1.5708,link2,0,0,1,100,1,-3.106,2.53,,,,,,,, +link4,-2.0098E-06,-0.033559,-0.18296,0,0,0,0.69687,0.0085449,4.7796E-08,-1.0943E-08,0.0080043,0.0020032,0.00084216,0,0,0,0,0,0,package://rml_63_description/meshes/link4.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link4.STL,,63连杆5-1,link_4,axis_4,joint4,revolute,0.069,-0.405,0.00029958,1.5708,0,0,link3,0,0,-1,100,1,-3.106,3.106,,,,,,,, +link5,-1.5679E-07,0.02862,-0.0062118,0,0,0,0.34759,0.00049457,-1.0235E-08,-1.8949E-09,0.00019706,-6.3439E-05,0.00044565,0,0,0,0,0,0,package://rml_63_description/meshes/link5.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link5.STL,,63连杆6-1,link_5,axis_5,joint5,revolute,0,0,0,1.5708,0,3.1416,link4,0,0,1,100,1,-3.106,3.106,,,,,,,, +link6,-0.0006163,0.00034085,-0.01449,0,0,0,0.077104,2.2947E-05,-1.3061E-06,1.1202E-07,2.1475E-05,-5.1151E-08,3.4243E-05,0,0,0,0,0,0,package://rml_63_description/meshes/link6.STL,1,1,1,1,0,0,0,0,0,0,package://rml_63_description/meshes/link6.STL,,末端法兰对外实体-1,link_6,axis_6,joint6,revolute,0,0.115,0,1.5708,0,3.1416,link5,0,0,-1,100,1,-6.28,6.28,,,,,,,, diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf new file mode 100644 index 0000000..dc01ad5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf @@ -0,0 +1,392 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf.xacro new file mode 100644 index 0000000..8abeb43 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_description/urdf/rml_63_gazebo.urdf.xacro @@ -0,0 +1,518 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + i + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/CMakeLists.txt new file mode 100644 index 0000000..3936f7a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_doc) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.1.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.1.pdf new file mode 100644 index 0000000..ae5eb1b Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.1.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.0.pdf new file mode 100644 index 0000000..9bba09d Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.0.pdf new file mode 100644 index 0000000..873cbe3 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.0.pdf new file mode 100644 index 0000000..5351e8b Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.1.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.1.pdf new file mode 100644 index 0000000..3bdf979 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.1.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.1.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.1.pdf new file mode 100644 index 0000000..aba35f5 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.1.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.0.pdf new file mode 100644 index 0000000..c3ec745 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.0.pdf new file mode 100644 index 0000000..3cea991 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机器人ROS2功能包简介..pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机器人ROS2功能包简介..pdf new file mode 100644 index 0000000..8f3afa2 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机器人ROS2功能包简介..pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.1.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.1.pdf new file mode 100644 index 0000000..204756e Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/English/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.1.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf new file mode 100644 index 0000000..656bf96 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.pdf new file mode 100644 index 0000000..7237d29 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/1. 睿尔曼 l ROS2机械臂rm_driver功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.pdf new file mode 100644 index 0000000..498c1c0 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/2. 睿尔曼 l ROS2机械臂rm_ros_interface功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.pdf new file mode 100644 index 0000000..803e56a Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/3. 睿尔曼 l ROS2机械臂rm_description功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.pdf new file mode 100644 index 0000000..704ed75 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/4. 睿尔曼 l ROS2机械臂rm_control功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.pdf new file mode 100644 index 0000000..68e6f40 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/5. 睿尔曼 l ROS2机械臂rm_moveit2_config详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.pdf new file mode 100644 index 0000000..9d0d753 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/6. 睿尔曼 l ROS2机械臂rm_bringup功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.pdf new file mode 100644 index 0000000..2d413f4 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/7. 睿尔曼 l ROS2机械臂rm_gazebo功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.pdf new file mode 100644 index 0000000..e629046 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/8. 睿尔曼 l ROS2机械臂rm_example功能包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.pdf new file mode 100644 index 0000000..2adb4f7 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2rm_driver话题详细说明V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2功能包简介V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2功能包简介V1.0.pdf new file mode 100644 index 0000000..b218c8f Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/doc/睿尔曼机械臂ROS2功能包简介V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/package.xml new file mode 100644 index 0000000..2cbbfab --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_doc/package.xml @@ -0,0 +1,18 @@ + + + + rm_doc + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/CMakeLists.txt new file mode 100755 index 0000000..e8d7856 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/CMakeLists.txt @@ -0,0 +1,62 @@ +cmake_minimum_required(VERSION 3.5) +project(rm_driver) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) +include_directories( + ${PROJECT_SOURCE_DIR} + ${PROJECT_SOURCE_DIR}/include + ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME} +) +link_directories(${catkin_LIB_DIRS} ${PROJECT_SOURCE_DIR}/lib) + +include_directories("/usr/local/lib") + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() +add_executable(rm_driver src/rm_driver.cpp) + + +set(RM_STATIC_LIBRARY "${CMAKE_CURRENT_SOURCE_DIR}/lib") + +# link_directories(${catkin_LIB_DIRS} ${CMAKE_CURRENT_SOURCE_DIR}/lib/RM_Service) +link_directories(${RM_STATIC_LIBRARY}) + +target_link_libraries(${PROJECT_NAME} + ${PROJECT_SOURCE_DIR}/lib/libapi_cpp.so +) + +ament_target_dependencies(rm_driver rclcpp std_msgs sensor_msgs rm_ros_interfaces) + +install(TARGETS rm_driver DESTINATION lib/${PROJECT_NAME}) + +install(DIRECTORY launch config + DESTINATION share/${PROJECT_NAME}) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README.md new file mode 100755 index 0000000..bdcc3ff --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README.md @@ -0,0 +1,167 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/README.md) + +
+ +
+ +# RealMan Robot rm_driver User Manual V1.5 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/7/2024 | Draft | +|V1.1 | 7/8/2024 | Amend(Add GEN72 adapter files) | +|V1.2 | 9/10/2024 | Amend(Add ECO63 adapter files) | +|V1.2.1 | 10/31/2024| Amend(Add dexterous hand udp topic) | +|V1.3 | 12/25/2024 | Amend(Add UDP reporting adaptation) | +|V1.4 | 4/7/2025 | Amend(Add UDP reporting adaptation) | +|V1.5 | 5/29/2025 | Revision (adapted to fourth generation controllers, added version query interface, added Cartesian space linear offset motion interface, added Modbus interface, added trajectory list interface. Please refer to the topic interface description document for details) | + +
+ +  + +## Content +* 1.rm_driver package description +* 2.rm_driver package use +* 2.1 Basic use of the package +* 2.2 Advanced use of the package +* 3.rm_driver package architecture description +* 3.1 Overview of Package Files +* 4.rm_driver topic description + + + +  +## 1. rm_driver package description +rm_driver package is very important in the ROS2 robotic arm package. This package realizes the function of controlling the robotic arm through communication between ROS and the robotic arm. The package will be introduced in detail in the following text through the following aspects: +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. + +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address:https://github.com/RealManRobot/ros2_rm_robot.git. +## 2. rm_driver package use +### 2.1 Basic use of the package +First, after configuring the environment and completing the connection, we can directly start the node and control the robotic arm through the following command. +The current control is based on the fact that we have not changed the IP of the robotic arm, which is still 192.168.1.18. +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65、eco63, gen72 and 75. +The following screen will appear if the underlying driver is successfully started. +![image](doc/rm_driver1.png) +### 2.2 Advanced use of the package +When our robotic arm's IP is changed, our start command is invalid. If we use the above command directly, we cannot successfully connect to the robotic arm. We can re-establish the connection by modifying the following configuration file. +The configuration file is located in the config folder under our rm_driver package. +![image](doc/rm_driver4.png) + +The contents of the configuration file are as follows: + +``` +rm_driver: + ros__parameters: + #robot param + arm_ip: "192.168.1.18" # Set the IP address for the TCP connection + tcp_port: 8080# # Set the port for the TCP connection + + arm_type: "RM_65" # set the robotic arm model + arm_dof: 6 # Set the degree of freedom of the robotic arm + + udp_ip: "192.168.1.10" # set the udp active reporting IP address + udp_cycle: 5 # the active reporting cycle of UDP, which needs to be a multiple of 5. + udp_port: 8089 # Set the udp active reporting port + udp_force_coordinate: 0 # Set the base coordinate of the six-axis force when the system is forced, where 0 is the sensor coordinate system, 1 is the current work coordinate system, and 2 is the current tool coordinate system + udp_hand: false # Set the udp hand reporting enable + udp_plus_base: false # Set the udp plus base reporting enable + udp_plus_state: false # Set the udp plus state reporting enable + trajectory_mode: 0 #When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode. + radio: 0 #Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect. + arm_joints: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"] +``` + +There are mainly the following parameters. +* arm_ip: This parameter represents the current IP of the robotic arm +* tcp_port: set the port when TCP is connected. +* arm_type: This parameter represents the current model of the robotic arm. The parameters that can be selected are RM_65 (65 series), RM_eco65 (ECO65 series), RM_eco63 (ECO63 series), RM_63 (63 series),GEN_72 (GEN72 series) and RM_75 (75 series). +* arm_dof: set the degree of freedom of the robotic arm. 6 is 6 degrees of freedom, and 7 is 7 degrees of freedom. +* udp_ip: set the udp active reporting IP address. +* udp_cycle: the active reporting cycle of UDP, which needs to be a multiple of 5. +* udp_port: set the udp active reporting port. +* udp_force_coordinate: set the base coordinate of the six-axis force when the system is forced, where 0 is the sensor coordinate system (original data), 1 is the current work coordinate system, and 2 is the current tool coordinate system. +* trajectory_mode:When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode. +* radio:Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect. +* In practice, we choose the corresponding launch file to start, which will automatically select the correct model. If there are special requirements, you can modify the corresponding parameters here. After modification, recompile the configuration in the workspace directory, and then the modified configuration will take effect. +Run the colcon build command in the workspace directory. + +``` +rm@rm-desktop: ~/ros2_ws$ colcon build +``` + +After successful compilation, follow the above commands to start the package. +## 3. rm_driver package architecture description +### 3.1 Overview of package files +The current rm_driver package is composed of the following files. + +``` +├── CMakeLists.txt # compilation rule file +├── config # config folder +│ ├── rm_63_config.yaml # 63 configuration file +│ ├── rm_65_config.yaml # 65 configuration file +│ ├── rm_75_config.yaml # 75 configuration file +│ ├── rm_eco65_config.yaml # eco65 configuration file +│ ├── rm_eco63_config.yaml # eco63 configuration file +│ └── rm_gen72_config.yaml # gen72 configuration file +├── doc +│ ├── RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md +│ ├── rm_driver1.png +│ ├── rm_driver2.png +│ ├── rm_driver3.png +│ ├── rm_driver4.png +│ └── 睿尔曼机械臂ROS2rm_driver话题详细说明.md +├── include # dependency header file folder +│ └── rm_driver +│ ├── cJSON.h # API header file +│ ├── constant_define.h # API header file +│ ├── rman_int.h # API header file +│ ├── rm_base_global.h # API header file +│ ├── rm_base.h # API header file +│ ├── rm_define.h # API header file +│ ├── rm_driver.h # rm_driver.cpp header file +│ ├── rm_praser_data.h # API header file +│ ├── rm_queue.h # API header file +│ ├── rm_service_global.h # API header file +│ ├── rm_service.h # API header file +│ └── robot_define.h # API header file +├── launch +│ ├── rm_63_driver.launch.py # 63 launch file +│ ├── rm_65_driver.launch.py # 65 launch file +│ ├── rm_75_driver.launch.py # 75 launch file +│ ├── rm_eco65_driver.launch.py # eco65 launch file +│ ├── rm_eco63_driver.launch.py # eco63 launch file +│ └── rm_gen72_driver.launch.py # gen72 launch file +├── lib +│ ├── libRM_Service.so -> libRM_Service.so.1.0.0 # API library file +│ ├── libRM_Service.so.1 -> libRM_Service.so.1.0.0 # API library file +│ ├── libRM_Service.so.1.0 -> libRM_Service.so.1.0.0 # API library file +│ ├── libRM_Service.so.1.0.0 # API library file +│ ├── linux_arm_service_release_v4.3.7.t7.tar.bz2 # API library file +│ └── linux_x86_service_release_v4.3.7.t7.tar.bz2 # API library file +├── package.xml # dependency declaration file +├── README_CN.md +├── README.md +└── src + └── rm_driver.cpp # driver code source file +``` + +### 4. rm_driver topic description +rm_driver has many topics, and you can learn about the topic information through the following commands. +![image](doc/rm_driver2.png) +![image](doc/rm_driver3.png) +It is mainly for the application of API to achieve some of the robotic arm functions; for a more complete introduction and use, please see the special document "[RealMan Robotic Arm ROS2 Topic Detailed Description](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md)". diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README_CN.md new file mode 100755 index 0000000..4100fdd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/README_CN.md @@ -0,0 +1,160 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/README.md) + +
+ +
+ +# 睿尔曼机器人rm_driver使用说明书V1.5 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-7 |拟制 | +|V1.1 |2024-7-8 |修订(添加GEN72适配文件) | +|V1.2 |2024-9-10 |修订(添加ECO63适配文件) | +|V1.2.1 |2024-10-31|修订(添加灵巧手高速适配) | +|V1.3 |2024-12-25|修订(添加UDP上报适配) | +|V1.4 |2024-12-25|修订(添加UDP上报适配) | +|V1.5 |2025-05-29|修订(适配四代控制器、添加版本查询接口、添加笛卡尔空间直线偏移运动接口、添加Modbus接口、添加轨迹列表接口详见话题接口说明文档)| + +
+ +## 目录 +* 1.[rm_driver功能包说明](#rm_driver功能包说明) +* 2.[rm_driver功能包使用](#rm_driver功能包使用) +* 2.1[功能包基础使用](#功能包基础使用) +* 2.2[功能包进阶使用](#功能包进阶使用) +* 3.[rm_driver功能包架构说明](#rm_driver功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4.[rm_driver话题说明](#rm_driver话题说明) + +## rm_driver功能包说明 +rm_driver功能包在机械臂ROS2功能包中是十分重要的,该功能包实现了通过ROS与机械臂进行通信控制机械臂的功能,在下文中将通过以下几个方面详细介绍该功能包。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 + +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用 +## rm_driver功能包使用 +### 功能包基础使用 +首先配置好环境完成连接后我们可以通过以下命令直接启动节点,控制机械臂。 +当前的控制基于我们没有改变过机械臂的IP即当前机械臂的IP仍为192.168.1.18。 +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。 +底层驱动启动成功后,将显示以下画面。 +![image](doc/rm_driver1.png) +### 功能包进阶使用 +当我们的机械臂IP被改变后我们的启动指令就失效了,再直接使用如上指令就无法成功连接到机械臂了,我们可以通过修改如下配置文件,重新建立连接。 +该配置文件位于我们的rm_driver功能包下的config文件夹下。 +![image](doc/rm_driver4.png) +其配置文件内容如下: + +``` +rm_driver: + ros__parameters: + #robot param + arm_ip: "192.168.1.18" #设置TCP连接时的IP + tcp_port: 8080 #设置TCP连接时的端口 + + arm_type: "RM_65" #机械臂型号设置 + arm_dof: 6 #机械臂自由度设置 + + udp_ip: "192.168.1.10" #设置udp主动上报IP + udp_cycle: 5 #udp主动上报周期,需要是5的倍数 + udp_port: 8089 #设置udp主动上报端口 + udp_force_coordinate: 0 #设置系统受力时六维力的基准坐标,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 + udp_hand: false #设置灵巧手udp主动上报使能 + udp_plus_base: false #设置末端设备基础信息udp主动上报使能 + udp_plus_state: false #设置末端设备实时信息udp主动上报使能 + + trajectory_mode: 0 #设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + radio: 0 #设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好 + arm_joints: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"] +``` + +其中主要有以下几个参数。 +* arm_ip:改参数代表机械臂当前的IP +* tcp_port:设置TCP连接时的端口。 +* arm_type:该参数代表机械臂当前的型号,可以选择的参数有RM_65(65系列)、RM_eco65(ECO65系列)、RM_eco63(ECO63系列)、RML_63(63系列)、RM_75(75系列)、GEN_72(GEN72系列)。 +* arm_dof: 机械臂自由度设置。6为6自由度,7为7自由度。 +* udp_ip: 设置udp主动上报目标IP。 +* udp_cycle:udp主动上报周期,需要是5的倍数。 +* udp_port:设置udp主动上报端口。 +* udp_force_coordinate:设置系统受力时六维力的基准坐标,0为传感器坐标系(原始数据) 1为当前工作坐标系 2为当前工具坐标系。 +* trajectory_mode:设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式 +* radio:设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好 +* 在实际使用时,我们选择对应的launch文件启动时会自动选择正确的型号,若有特殊要求可在此处进行相应的参数修改,修改之后需要在工作空间目录下进行重新编译,之后修改的配置才会生效。 +* 在工作空间目录运行colcon build指令。 + +``` +rm@rm-desktop: ~/ros2_ws$ colcon build +``` + +* 编译成功后可按如上指令进行功能包启动。 +## rm_driver功能包架构说明 +### 功能包文件总览 +当前rm_driver功能包的文件构成如下。 + +``` +├── CMakeLists.txt #编译规则文件 +├── config #配置文件夹 +│ ├── rm_63_config.yaml #63配置文件 +│ ├── rm_65_config.yaml #65配置文件 +│ ├── rm_75_config.yaml #75配置文件 +│ ├── rm_eco65_config.yaml #eco65配置文件 +│ ├── rm_eco63_config.yaml #eco63配置文件 +│ └── rm_gen72_config.yaml #gen725配置文件 +├── doc +│ ├── RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md +│ ├── rm_driver1.png +│ ├── rm_driver2.png +│ ├── rm_driver3.png +│ ├── rm_driver4.png +│ └── 睿尔曼机械臂ROS2rm_driver话题详细说明.md +├── include #依赖头文件文件夹 +│ └── rm_driver +│ ├── cJSON.h #API头文件 +│ ├── constant_define.h #API头文件 +│ ├── rman_int.h #API头文件 +│ ├── rm_base_global.h #API头文件 +│ ├── rm_base.h #API头文件 +│ ├── rm_define.h #API头文件 +│ ├── rm_driver.h #rm_driver.cpp头文件 +│ ├── rm_praser_data.h #API头文件 +│ ├── rm_queue.h #API头文件 +│ ├── rm_service_global.h #API头文件 +│ ├── rm_service.h #API头文件 +│ └── robot_define.h #API头文件 +├── launch +│ ├── rm_63_driver.launch.py #63启动文件 +│ ├── rm_65_driver.launch.py #65启动文件 +│ ├── rm_75_driver.launch.py #75启动文件 +│ ├── rm_eco65_driver.launch.py #eco65启动文件 +│ ├── rm_eco63_driver.launch.py #eco63启动文件 +│ └── rm_gen72_driver.launch.py #gen72启动文件 +├── lib +│ ├── libRM_Service.so -> libRM_Service.so.1.0.0 #API库文件 +│ ├── libRM_Service.so.1 -> libRM_Service.so.1.0.0 #API库文件 +│ ├── libRM_Service.so.1.0 -> libRM_Service.so.1.0.0 #API库文件 +│ ├── libRM_Service.so.1.0.0 #API库文件 +│ ├── linux_arm_service_release_v4.3.7.t7.tar.bz2 #API库文件 +│ └── linux_x86_service_release_v4.3.7.t7.tar.bz2 #API库文件 +├── package.xml #依赖声明文件 +├── README_CN.md +├── README.md +└── src + └── rm_driver.cpp #驱动代码源文件 +``` + +## rm_driver话题说明 +rm_driver的话题较多,可以通过如下指令了解其话题信息。 +![image](doc/rm_driver2.png) +![image](doc/rm_driver3.png) +主要为套用API实现的一些机械臂本体的功能,其详细介绍和使用在此不详细展开,可以通过专门的文档《[睿尔曼机械臂ROS2话题详细说明](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)》进行查看。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml new file mode 100755 index 0000000..815b723 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml @@ -0,0 +1,21 @@ +rm_driver: + ros__parameters: + #robot param + arm_ip: "192.168.1.18" #设置TCP连接时的IP + tcp_port: 8080 #设置TCP连接时的端口 + + arm_type: "RM_65" #机械臂型号设置 + arm_dof: 6 #机械臂自由度设置 + + udp_ip: "192.168.1.10" #设置udp主动上报IP + udp_cycle: 5 #udp主动上报周期,需要是5的倍数。 + udp_port: 8089 #设置udp主动上报端口 + udp_force_coordinate: 0 #设置系统受力时六维力的基准坐标,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 + udp_hand: false #设置灵巧手udp主动上报使能 + udp_plus_base: false #设置末端设备基础信息udp主动上报使能 + udp_plus_state: false #设置末端设备实时信息udp主动上报使能 + + trajectory_mode: 0 #设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + radio: 0 #设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好 + + arm_joints: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"] diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md new file mode 100755 index 0000000..1e62f46 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md @@ -0,0 +1,1128 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md) + +
+ +
+ +# RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2) V1.1.6 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :---- | :---: | +|V1.0 | 2024-2-18 | Draft | +|V1.1 | 2024-7-8 | Amend(Add teaching instructions3.6) | +|V1.1.1| 2024-8-13| Amend(Add six-axis topic) | +|V1.1.2| 2024-9-25| Amend(revise coordinate topic description)| +|V1.1.3| 2024-10-31|Amend(Add Agile Hand UDP Adaptation,Follow Adaptation)| +|V1.1.4| 2024-12-25|Amend(Modify UDP report content)| +|V1.1.5| 2025-02-19|Amend(API2 Adaptation; add end ecosystem protocol interface; update UDP interface) | +|V1.1.6| 2025-05-26|Revision (adapted to fourth generation controllers, added version query interface, added Cartesian space linear offset motion interface, added Modbus interface, added trajectory list interface)| + +
+ +## Content + +* 1.[Introduction](#Introduction) +* 2.[Error Description](#Error_Description) +* 2.1[Controller error type](#Controller_error_type) +* 2.2[Joint error type](#Joint_error_type) +* 2.3[API error type](#API_error_type) +* 3.[ROS Function Package Robotic Arm Instructions](#ROS_Function_Package_Robotic_Arm_Instructions) +* 3.1[Joint Configuration](#Joint_Configuration) +* 3.1.1[Clear the joint's error code](#Clear_the_joint's_error_code) +* 3.2[Get version](#Get_version) +* 3.2.1[Get basic information of robotic arm](#Get_basic_information_of_robotic_arm) +* 3.2.2[Get the software information of the robotic arm](#Get_the_software_information_of_the_robotic_arm) +* 3.2.3[Get the joint software version](#Get_the_joint_software_version) +* 3.2.4[Get the software version of the end interface board](#Get_the_software_version_of_the_end_interface_board) +* 3.3[Functions related to the work coordinate system settings](#Functions_related_to_the_work_coordinate_system_settings) +* 3.3.1[Change the current work coordinate system](#Change_the_current_work_coordinate_system) +* 3.4[Coordinate system query](#Coordinate_system_query) +* 3.4.1[Get the current tool coordinate system](#Get_the_current_tool_coordinate_system) +* 3.4.2[Get all tool coordinate system names](#Get_all_tool_coordinate_system_names) +* 3.4.3[Get the current work coordinate system](#Get_the_current_work_coordinate_system) +* 3.4.4[Get all work coordinate system names](#Get_all_work_coordinate_system_names) +* 3.5[Functions related to the arm state query](#Functions_related_to_the_arm_state_query) +* 3.5.1[Get the current state of the robot arm - return each joint angle + Euler angle](#Get_the_current_state_of_the_robot_arm-return_each_joint_angle_and_Euler_angle) +* 3.5.2[Get the current state of the robotic arm - return each joint radians + quaternion](#Get_the_current_state_of_the_robotic_arm-return_each_joint_radians_and_quaternion) +* 3.6[Functions related to motion planning of the robotic arm](#Functions_related_to_motion_planning_of_the_robotic_arm) +* 3.6.1[Joint Space Motion](#Joint_Space_Motion) +* 3.6.2[Linear motion in Cartesian space](#Linear_motion_in_Cartesian_space) +* 3.6.3[Cartesian space linear offset motion](#Cartesian_space_linear_offset_motion) +* 3.6.4[Circular motion in Cartesian space](#Circular_motion_in_Cartesian_space) +* 3.6.5[Joint angle CANFD transmission](#Joint_angle_CANFD_transmission) +* 3.6.6[Customize high following mode joint angle CANFD transmission](#Customize_high_following_mode_joint_angle_CANFD_transmission) +* 3.6.7[Pose CANFD transmission](#Pose_CANFD_transmission) +* 3.6.8[Customize high following mode pose CANFD transmission](#Customize_high_following_mode_pose_CANFD_transmission) +* 3.6.9[Joint space planning to target pose](#Joint_space_planning_to_target_pose) +* 3.6.10[Trajectory emergency stop](#Trajectory_emergency_stop) +* 3.6.11[Emergency stop](#Emergency_stop) +* 3.7[Teaching instructions](#Teaching_instructions) +* 3.7.1[Joint teaching](#Joint_teaching) +* 3.7.2[Position teaching](#Position_teaching) +* 3.7.3[Attitude teaching](#Attitude_teaching) +* 3.7.4[Stop teaching](#Stop_teaching) +* 3.8[Trajectory File](#Trajectory_File) +* 3.8.1[Query Trajectory List ](#Query_Trajectory_List) +* 3.8.2[Start Running Specified Trajectory](#Start_Running_Specified_Trajectory) +* 3.8.3[Delete Specified Trajectory File](#Delete_Specified_Trajectory_File) +* 3.8.4[Save Trajectory File](#Save_Trajectory_File) +* 3.8.5[Query Flowchart Program Run State](#Query_Flowchart_Program_Run_State) +* 3.9[Modbus Configuration](#Modbus_Configuration) +* 3.9.1[Set Controller RS485 Mode](#Set_Controller_RS485_Mode) +* 3.9.2[Get Controller RS485 Mode](#Get_Controller_RS485_Mode) +* 3.9.3[Set Tool End RS485 Mode](#Set_Tool_End_RS485_Mode) +* 3.9.4[Get Tool End RS485 Mode](#Get_Tool_End_RS485_Mode) +* 3.10[ModbusTCP Master](#ModbusTCP_Master) +* 3.10.1[Add Modbus TCP Master](#Add_Modbus_TCP_Master) +* 3.10.2[Update Modbus TCP Master](#Update_Modbus_TCP_Master) +* 3.10.3[Delete Modbus TCP Master](#Delete_Modbus_TCP_Master) +* 3.10.4[Get Specified Modbus TCP Master](#Get_Specified_Modbus_TCP_Master) +* 3.10.5[Get Modbus TCP Master List](#Get_Modbus_TCP_Master_List) +* 3.11[Tool end controller end RTU Modbus protocol reads and writes data](#Tool_end_controller_end_RTU_Modbus_protocol_reads_and_writes_data) +* 3.11.1[Modbus RTU Protocol Read Coils](#Modbus_RTU_Protocol_Read_Coils) +* 3.11.2[Modbus RTU Protocol Write Coils](#Modbus_RTU_Protocol_Write_Coils) +* 3.11.3[Modbus RTU Protocol Read Discrete Inputs](#Modbus_RTU_Protocol_Read_Discrete_Inputs) +* 3.11.4[Modbus RTU Protocol Read Holding Registers](#Modbus_RTU_Protocol_Read_Holding_Registers) +* 3.11.5[Modbus RTU Protocol Write Holding Registers](#Modbus_RTU_Protocol_Write_Holding_Registers) +* 3.11.6[Modbus RTU Protocol Read Input Registers](#Modbus_RTU_Protocol_Read_Input_Registers) +* 3.12[Controller Modbus TCP protocol reads and writes data](#Controller_Modbus_TCP_protocol_reads_and_writes_data) +* 3.12.1[Modbus TCP Protocol Read Coils](#Modbus_TCP_Protocol_Read_Coils) +* 3.12.2[Modbus TCP Protocol Write Coils](#Modbus_TCP_Protocol_Write_Coils) +* 3.12.3[Modbus TCP Protocol Read Discrete Inputs](#Modbus_TCP_Protocol_Read_Discrete_Inputs) +* 3.12.4[Modbus TCP Protocol Read Holding Registers](#Modbus_TCP_Protocol_Read_Holding_Registers) +* 3.12.5[Modbus TCP Protocol Write Holding Registers](#Modbus_TCP_Protocol_Write_Holding_Registers) +* 3.12.5[Modbus TCP Protocol Read Input Registers](#Modbus_TCP_Protocol_Read_Input_Registers) +* 3.13[Functions related to the IO configuration of the end tool](#Functions_related_to_the_IO_configuration_of_the_end_tool) +* 3.13.1[Setting the tool voltage output](#Setting_the_tool_voltage_output) +* 3.14[Functions related to the control of the end gripper - optional](#Functions_related_to_the_control_of_the_end_gripper) +* 3.14.1[Setting the Gripper Pick](#Setting_the_Gripper_Pick) +* 3.14.2[Setting the gripper pick-on](#Setting_the_gripper_pick-on) +* 3.14.3[Setting the gripper to the given position](#Setting_the_gripper_to_the_given_position) +* 3.15[Functions related to the drag teach and trajectory reproduction](#Functions_related_to_the_drag_teach_and_trajectory_reproduction) +* 3.15.1[Set the force-position mixing control](#Set_the_force-position_mixing_control) +* 3.15.2[Stop the force-position mixing control](#Stop_the_force-position_mixing_control) +* 3.16[Functions related to the use of six-axis force sensors at the end - optional](#Functions_related_to_the_use_of_six-axis_force_sensors_at_the_end) +* 3.16.1[Query the six-axis force data](#Query_the_six-axis_force_data) +* 3.16.2[Clearing the six-axis force Data](#Clearing_the_six-axis_force_Data) +* 3.17[Functions related to the control of the five-finger dexterous hand - optional](#Functions_related_to_the_control_of_the_five-finger_dexterous_hand) +* 3.17.1[Setting the serial number of the dexterous hand posture](#Setting_the_serial_number_of_the_dexterous_hand_posture) +* 3.17.2[Set the dexterous hand action sequence number](#Set_the_dexterous_hand_action_sequence_number) +* 3.17.3[Setting the angles of various degrees of freedom for the dexterous hand](#Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand) +* 3.17.4[Setting the dexterous hand speed](#Setting_the_dexterous_hand_speed) +* 3.17.5[Setting the force threshold of the dexterous hand](#Setting_the_force_threshold_of_the_dexterous_hand) +* 3.17.6[Setting the angle following of the dexterous hand](#Setting_the_angle_following_of_the_dexterous_hand) +* 3.17.7[Setting the posture following of the dexterous hand](#Setting_the_posture_following_of_the_dexterous_hand) +* 3.18[Lifting mechanism](#Lifting_mechanism) +* 3.18.1[Speed open-loop control of the lifting mechanism](#Speed_open-loop_control_of_the_lifting_mechanism) +* 3.18.2[Position closed-loop control of the lifting mechanism](#Position_closed-loop_control_of_the_lifting_mechanism) +* 3.18.3[Get the lifting mechanism state](#Get_the_lifting_mechanism_state) +* 3.19[End-Effector Ecosystem Command Set](#End_Effector_Ecosystem_Command_Set) +* 3.19.1[Setting End-Effector Ecosystem Protocol Mode](#Setting_End_Effector_Ecosystem_Protocol_Mode) +* 3.19.2[Querying End-Effector Ecosystem Protocol Mode](#Querying_End_Effector_Ecosystem_Protocol_Mode) +* 3.19.3[Setting Tactile Sensor Mode](#Setting_Tactile_Sensor_Mode) +* 3.19.4[Querying Tactile Sensor Mode](#Querying_Tactile_Sensor_Mode) +* 3.20[Functions related to the transmissive force-position compensation Mode](#Functions_related_to_the_transmissive_force-position_compensation_Mode) +* 3.20.1[Starting the transmissive force-position mixing control compensation mode](#Starting_the_transmissive_force-position_mixing_control_compensation_mode) +* 3.20.2[Stopping the transmissive force-position mixing control compensation mode](#Stopping_the_transmissive_force-position_mixing_control_compensation_mode) +* 3.20.3[Transmissive force-position mixing control compensation - joint](#Transmissive_force-position_mixing_control_compensation-joint) +* 3.20.4[Transmissive force-position mixing control compensation - pose](#Transmissive_force-position_mixing_control_compensation-pose) +* 3.21[Robotic arm state active reporting](#Robotic_arm_state_active_reporting) +* 3.21.1[Setting UDP robotic arm state active reporting configuration](#Setting_UDP_robotic_arm_state_active_reporting_configuration) +* 3.21.2[Getting UDP robotic arm state active reporting configuration](#Getting_UDP_robotic_arm_state_active_reporting_configuration) +* 3.21.3[UDP robotic arm state active reporting](#UDP_robotic_arm_state_active_reporting) + +## Introduction + +RealMan provides ROS2 function packages based on API to help users control the robotic arm using ROS2. If you want to learn more about controlling the robotic arm, you can refer to the API documentation and instructions. In practical use, the user can establish communication with the robotic arm through the Ethernet port and control the robotic arm. + +## Error_Description + +### Controller_error_type + +| Serial No. | Error code (hexadecimal) | Error content | +| :---: | :---- | :---: | +| 1 | 0x0000 | System is normal | +| 2 | 0x1001 | Joint communication is abnormal | +| 3 | 0x1002 | The target angle exceeds the limit | +| 4 | 0x1003 | This position is inaccessible and is a singular point | +| 5 | 0x1004 | Real-time kernel communication error | +| 6 | 0x1005 | Joint communication bus error | +| 7 | 0x1006 | Planning layer kernel error | +| 8 | 0x1007 | Joint Overspeed | +| 9 | 0x1008 | The end interface board cannot be connected | +| 10 | 0x1009 | Overspeed limit | +| 11 | 0x100A | Overacceleration limit | +| 12 | 0x100B | Joint brake is not opened | +| 13 | 0x100C | Overspeed during drag teach | +| 14 | 0x100D | Robotic arm collision | +| 15 | 0x100E | No work coordinate system is available | +| 16 | 0x100F | No tool coordinate system is available | +| 17 | 0x1010 | Joint failure enabling error | + +### Joint_error_type + +| Serial No. | Error code (hexadecimal) | Error content | +| :---: | :---- | :---: | +| 1 | 0x0000 | Joint is normal | +| 2 | 0x0001 | FOC error | +| 3 | 0x0002 | Overvoltage | +| 4 | 0x0004 | Undervoltage | +| 5 | 0x0008 | Overtemperature | +| 6 | 0x0010 | Start failed | +| 7 | 0x0020 | Encoder error | +| 8 | 0x0040 | Overcurrent | +| 9 | 0x0080 | Software error | +| 10 | 0x0100 | Temperature sensor error | +| 11 | 0x0200 | Position limit-out error | +| 12 | 0x0400 | Illegal joint ID | +| 13 | 0x0800 | Position tracking error | +| 14 | 0x1000 | Current detection error | +| 15 | 0x2000 | Brake opening failed | +| 16 | 0x4000 | Position command step warning | +| 17 | 0x8000 | Multi-coil joint's coil lost the number | +| 18 | 0xF000 | Communication frame loss | + +### API_error_type + +| Error Code (int) | Description | Resolution | +| :---: | :---- | :--- | +| 0 | System operating normally. | - | +| 1 | Message request returned FALSE. |- Verify JSON command:
① Enable API DEBUG logs to capture raw JSON data.
② Check JSON syntax: Ensure correct formatting of brackets, quotes, commas, etc. (use a JSON validation tool).
③ Refer to API documentation to validate parameter names, data types, and value ranges.
④ After fixing issues, resend the command and check the status code and business data returned by the controller.
- Check robot arm status:
① Review real-time error messages in the robot arm controller or logs (e.g., hardware failures, limits exceeded), and reset, calibrate, or troubleshoot hardware issues as indicated.
② After resolving issues, resend the command and check the status code and business data returned by the controller.| +| -1 | Data send failure, communication issue during transmission. | Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.| +| -2 | Data receive failure, communication issue during transmission or controller timeout without response.|- Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.
- Verify version compatibility:
① Confirm that the controller firmware version supports the current API functionality. Refer to the [version change notes](https://develop.realman-robotics.com/robot4th/releaseNotes/releaseNotesfour/) for specific version compatibility.
② If the version is too low, upgrade the controller or use a compatible API version.
- When calling ModbusTCP interface: Applicable only when reading/writing to the controller's ModbusTCP device. After creating the robot arm control handle, you must call the rm_set_modbustcp_mode() interface, otherwise, no return value will be received.| +| -3 | Return value parsing failure, received data format is incorrect or incomplete.|Verify version compatibility:
① Confirm that the controller firmware version supports the current API functionality. Refer to the [version change notes](https://develop.realman-robotics.com/robot4th/releaseNotes/releaseNotesfour/) for specific version compatibility.
② If the version is too low, upgrade the controller or use a compatible API version.| +| -4 | Current device validation failed, i.e., the current device is not a joint/elevator/gripper/dexterous hand.| - Check for concurrent control of multiple devices: Ensure no other devices are sending motion commands to the robot arm, including movements of the robot arm, gripper, dexterous hand, and elevator.
- Real-time monitoring of command events: Register the callback function rm_get_arm_event_call_back:
① Capture device arrival events (e.g., motion completion, timeout);
② Use the device parameter in the callback to determine the specific type of device that triggered the event. | +| -5 | Single-threaded blocking mode timed out without receiving a response, ensure the timeout setting is reasonable.| - Check timeout duration settings: In single-threaded blocking mode, you can configure the timeout for waiting for device motion completion. Ensure the timeout setting is greater than the device motion time.
- Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.| + +## ROS_Function_Package_Robotic_Arm_Instructions + +This section describes how to query and control the robotic arm through the topic of ROS. + +### Joint_Configuration + +#### Clear_the_joint's_error_code + +| Function description | Clear_the_joint's_error_code | +| :---: | :---- | +| Parameter description | Jointerrclear.msg
uint8 joint_num: The corresponding joint number, from the base to the end-effector of the robotic arm. For a 6-DoF arm, the joint numbers are sequentially 1 to 6. For a 7-DoF arm, the joint numbers are sequentially 1 to 7. | +| Command example | ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1 " | +| Return value | true-set successfully,false-set failed | +| Return example | ros2 topic echo /rm_driver/set_joint_err_clear_result | + +### Get_version + +#### Get_basic_information_of_robotic_arm + +| Function description | Get_basic_information_of_robotic_arm | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty. | +| Command example | ros2 topic pub --once /rm_driver/get_robot_info_cmd std_msgs/msg/Empty "{}" | +| Return value | RobotInfo.msg
uint8 arm_dof: The degrees of freedom of the robotic arm (number of joints)
uint8 arm_model: The model of the robotic arm. Examples: 0=RM_65, 1=RM_75, 2=RML_63I (deprecated), 3=RML_63II, 4=RML_63III, 5=ECO_65, 6=ECO_62, 7=GEN_72, 8=ECO63, 9=Generic Robot
uint8 force_type: The version of the end-effector force sensor. Examples: 0=Standard, 1=One-Dimensional Force, 2=Six-Dimensional Force, 3=Integrated Six-Dimensional Force
uint8 robot_controller_version: The version of the robotic arm controller (3: Third Generation, 4: Fourth Generation)
bool state: Whether the reading was successful. | +| Return example | ros2 topic echo /rm_driver/get_robot_info_result | + +#### Get_the_software_information_of_the_robotic_arm + +| Function description | Get_the_software_information_of_the_robotic_arm | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty. | +| Command example | ros2 topic pub --once /rm_driver/get_arm_software_version_cmd std_msgs/msg/Empty "{}" | +| Return value | Armsoftversion.msg
string product_version: The model of the robotic arm
string controller_version: The version of the robotic arm controller. If it is a fourth-generation controller, this field will be "4.0"
string algorithm_info: Algorithm library information
Softwarebuildinfo ctrl_info: Software information for the control layer
string dynamic_info: Dynamics version (third generation)
Softwarebuildinfo plan_info: Software information for the planning layer (third generation)
Softwarebuildinfo com_info: Software information for the communication module (fourth generation)
Softwarebuildinfo program_info: Software information for the flowchart programming module (fourth generation)
bool state: Query status - true for success, false for failure | +| Return example | ros2 topic echo /rm_driver/get_arm_software_version_result | + +#### Get_the_joint_software_version + +| Function description | Get_the_joint_software_version | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty. | +| Command example | ros2 topic pub --once /rm_driver/get_joint_software_version_cmd std_msgs/msg/Empty "{}" | +| Return value | Jointversion.msg
string[7] joint_version: An array of software version numbers for each joint obtained. These need to be converted to hexadecimal. For example, if a joint version obtained is 54536, converting it to hexadecimal gives D508, which means the current joint version is Vd5.0.8 (for third-generation controllers).
bool state: Acquisition status - true for successful acquisition, false for failed acquisition. | +| Return example | ros2 topic echo /rm_driver/get_joint_software_version_result | + +#### Get_the_software_version_of_the_end_interface_board + +| Function description | Get_the_software_version_of_the_end_interface_board | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty. | +| Command example | ros2 topic pub --once /rm_driver/get_tool_software_version_cmd std_msgs/msg/Empty "{}" | +| Return value | Toolsoftwareversionv4.msg
string tool_version: The software version number of the end-effector interface board
bool state: Query status, returns true for success, false for failure | +| Return example | ros2 topic echo /rm_driver/get_tool_software_version_result | + +### Functions_related_to_the_work_coordinate_system_settings + +#### Change_the_current_work_coordinate_system + +| Function description | Change_the_current_work_coordinate_system | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::String | +| Command example | ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'" | +| Return value | true-set successfully,false-set failed | +| Return example | ros2 topic echo /rm_driver/change_work_frame_result | + +### Coordinate_system_query + +#### Get_the_current_tool_coordinate_system + +| Function description | Get_the_current_tool_coordinate_system | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}" | +| Return value | Current tool coordinate system name | +| Return example | ros2 topic echo /rm_driver/get_current_tool_frame_result | + +#### Get_all_tool_coordinate_system_names + +| Function description | Get_all_tool_coordinate_system_names | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}" | +| Return value | All names of the current tool coordinate system | +| Return example | ros2 topic echo /rm_driver/get_all_tool_frame_result | + +#### Get_the_current_work_coordinate_system + +| Function description | Get_the_current_work_coordinate_system | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" | +| Return value | true-set successfully,false-set failed | +| Return example | ros2 topic echo /rm_driver/get_curr_workFrame_result | + +#### Get_all_work_coordinate_system_names + +| Function description | Get_all_work_coordinate_system_names | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}" | +| Return value | All work coordinate system names | +| Return example | ros2 topic echo /rm_driver/get_all_work_frame_result | + +### Functions_related_to_the_arm_state_query + +#### Get_the_current_state_of_the_robot_arm-return_each_joint_angle_and_Euler_angle + +| Function description | Retrieve the current state of the robotic arm | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" | +| Return value | The current robotic arm joint state (angle) + pose information (Euler angle) + error information | +| Return example | ros2 topic echo /rm_driver/get_current_arm_original_state_result | + +#### Get_the_current_state_of_the_robotic_arm-return_each_joint_radians_and_quaternion + +| Function description | Retrieve the current state of the robotic arm | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" | +| Return value | The current robotic arm joint state (radians) + pose information (quaternion) + error information | +| Return example | ros2 topic echo /rm_driver/get_current_arm_state_result | + +### Functions_related_to_motion_planning_of_the_robotic_arm + +#### Joint_Space_Motion + +| Function description | Joint space move MOVEJ | +| :---: | :---- | +| Parameter description | Movej.msg
float32[6] joint: joint angle, unit: radians.
uint8 speed: speed percentage ratio coefficient, 0~100.
bool block: whether it is a blocking mode,bool type,true:blocking,false:non-blocking. | +| Command example | 6-degree of freedom
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0]
speed: 20
block: true
dof: 6"
7-degree of freedom
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0, 0]
speed: 20
block: true
trajectory_connect: 0
dof: 7" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/movej_result | + +#### Linear_motion_in_Cartesian_space + +| Function description | Linear motion in Cartesian space MOVEL | +| :---: | :---- | +| Parameter description | Movel.msg
geometry_msgs/Pose pose: robotic arm pose,geometry_msgs/Pose type,x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0~100。
bool : whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | First, use MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: -0.317239
y: 0.120903
z: 0.255765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
block: true"
Then use MoveL
ros2 topic pub --once /rm_driver/movel_cmd rm_ros_interfaces/msg/Movel "pose:
position:
x: -0.317239
y: 0.120903
z: 0.295765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
trajectory_connect: 0
block: true" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/movel_result | + +#### Cartesian_space_linear_offset_motion + +| Function description | Cartesian_space_linear_offset_motion | +| :---: | :---- | +| Parameter description | Moveloft.msg
geometriy_msgs/Pose pose: Position and attitude offset, position unit: meters, attitude unit: radians
int32 speed: velocity percentage coefficient, 1-100
int32 r: blending radius percentage coefficient, 0-100.
Bool trajectory_connect: Trajectory connection flag, 0 immediately plans and executes the trajectory, without connecting to subsequent trajectories. 1: Plan the current trajectory together with the next trajectory, but do not execute it immediately. In blocking mode, even if the transmission is successful, it will immediately return.
Bool frame_type: reference coordinate system type, 0 working coordinates, 1 tool coordinates
bool block: block setting. In multi-threaded mode, 0 represents non blocking mode, which returns immediately after sending an instruction; 1 represents blocking mode, waiting for the robotic arm to reach the target position or planning failure before returning. In single threaded mode, 0 represents non blocking mode, which returns immediately after sending an instruction; When using other values, block the mode and set a timeout based on the movement time, in seconds. | +| Command example | First, use MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.255765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}},speed: 20, trajectory_connect: 0, block: true}"
Then use Movel_offset
ros2 topic pub --once /rm_driver/movel_offset_cmd rm_ros_interfaces/msg/Moveloffset "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.295765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}}, speed: 20 ,r: 0 ,trajectory_connect: false, frame_type: false,block: false}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/movel_offset_result | + +#### Circular_motion_in_Cartesian_space + +| Function description | Circular motion in Cartesian space MOVEC | +| :---: | :---- | +| Parameter description | Movec.msg
geometry_msgs/Pose pose_mid: middle pose,geometry_msgs/Pose type,x, y, z coordinates (float type, unit: m) + quaternion.
geometry_msgs/Pose pose_end: end pose,geometry_msgs/Posetype, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0-100.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | First, use movej_p to reach the specified position
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: 0.274946
y: -0.058786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 0
block: true"
Use movec to reach the specified position
ros2 topic pub --once /rm_driver/movec_cmd rm_ros_interfaces/msg/Movec "pose_mid:
position:
x: 0.324946
y: -0.008786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
pose_end:
position:
x: 0.274946
y: 0.041214
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 20
trajectory_connect: 0
block: false
loop: 0" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/movec_result | + +#### Joint_angle_CANFD_transmission + +| Function description | Joint angle CANFD transmission | +| :---: | :---- | +| Parameter description | Jointpos.msg
float32[6] joint: joint angle, unit: radians.
bool follow: follow state, true: high following, false: low following, default high following if not set.
float32 expand: expand joint, unit: radians. | +| Command example | Transmission needs to send multiple continuous points to achieve, simply by the following command and can not achieve the function, the current moveit2 control using angle transmission control mode.
ros2 topic pub /rm_driver/movej_canfd_cmd rm_ros_interfaces/msg/Jointpos "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
dof: 6" | +| Return value | Success: no return value; Failure return: the driver terminal returns an error code. | + +#### Customize_high_following_mode_joint_angle_CANFD_transmission + +| Function description | Customize high following mode joint angle CANFD transmission | +| :---: | :---- | +| Parameter description | Jointposcustom.msg
float32[6] joint: joint angle, unit: radians.
bool follow: follow state, true: high following, false: low following, default high following if not set.
float32 expand: expand joint, unit: radians.
uint8 trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
uint8 radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.| +| Command example | Transmission needs to send multiple continuous points to achieve, simply by the following command and can not achieve the function, the current moveit2 control using angle transmission control mode.
ros2 topic pub /rm_driver/movej_canfd_custom_cmd rm_ros_interfaces/msg/Jointposcustom "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
trajectory_mode: 0
radio: 0
dof: 6" | +| Return value | Success: no return value; Failure return: the driver terminal returns an error code. | + +#### Pose_CANFD_transmission + +| Function description | Pose CANFD transmission | +| :---: | :---- | +| Parameter description | Cartepos.msg
geometry_msgs/Pose pose: transmission pose, geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion.
bool follows: follow state, true: high following, false: low following, default high following if not set. | +| Command example | It needs to be a large number (10 or more) of continuous position points, simply by the following command and can not achieve the function, with more than a 2ms period continuous release.
ros2 topic pub /rm_driver/movep_canfd_cmd rm_ros_interfaces/msg/Cartepos "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false" | +| Return value | Success: no return value; Failure return: the driver terminal returns an error code. | + +#### Customize_high_following_mode_pose_CANFD_transmission + +| Function description | Customize high following mode pose CANFD transmission | +| :---: | :---- | +| Parameter description | Carteposcustom.msg
geometry_msgs/Pose pose: transmission pose, geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion.
bool follows: follow state, true: high following, false: low following, default high following if not set.
uint8 trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
uint8 radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.| +| Command example | It needs to be a large number (10 or more) of continuous position points, simply by the following command and can not achieve the function, with more than a 2ms period continuous release.
ros2 topic pub /rm_driver/movep_canfd_custom_cmd rm_ros_interfaces/msg/Carteposcustom "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false
trajectory_mode: 0
radio: 0" | +| Return value | Success: no return value; Failure return: the driver terminal returns an error code. | + +#### Joint_space_planning_to_target_pose + +| Function description | Joint space planning to target pose MOVEJP | +| :---: | :---- | +| Parameter description | Movejp.msg
geometry_msgs/Pose target pose, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0-100.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: -0.317239
y: 0.120903
z: 0.255765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
block: true" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/movej_p_result | + +#### Trajectory_emergency_stop + +| Function description | Motion planning trajectory emergency stop | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}"| +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/move_stop_result | + +#### Emergency_stop + +| Function description | Emergency_stop | +| :---: | :---- | +| Parameter description | rm_ros_interfaces/Stop Emergency stop status, true: E-stopped, false: Resumed | +| Command example | ros2 topic pub --once /rm_driver/emergency_stop_cmd rm_ros_interfaces/Stop "state: true" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/emergency_stop_result | + +### Teaching_instructions + +#### Joint_teaching + +| Function description | Joint teaching | +| :---: | :---- | +| Parameter description | Jointteach.msg
uint8 num:Joint num,1~7
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100. | +| Command example | ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1
direction: 0
speed: 10" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_joint_teach_result | + +#### Position_teaching + +| Function description | Position teaching | +| :---: | :---- | +| Parameter description | Posteach.msg
uint8 type: Teaching demonstration type: input0:X-axis direction、1:Y-axis direction、2:Z-axis direction
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100.| +| Command example | ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2
direction: 0
speed: 10" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_pos_teach_result | + +#### Attitude_teaching + +| Function description | Attitude teaching | +| :---: | :---- | +| Parameter description | Ortteach.msg.msg
uint8 type: Teaching demonstration type: input0:RX-axis direction、1:RY-axis direction、2:RZ-axis direction
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100. | +| Command example | ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2
direction: 0
speed: 10" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_ort_teach_result | + +#### Stop_teaching + +| Function description | Stop teaching | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty| +| Command example | ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_stop_teach_result | + +### Trajectory_File + +#### Query_Trajectory_List + +| Function description | Query_Trajectory_List | +| :---: | :---- | +| Parameter description | GettraInjectorylist.msg
int32 page_num: Page number.
Int32 page_size: The size of each page.
String vague_search: Fuzzy search.| +| Command example | ros2 topic pub --once /rm_driver/get_trajectory_file_list_cmd rm_ros_interfaces/msg/Gettrajectorylist "{page_num: 1,page_size: 10,vague_search: 's'}" | +| Return value | Trajectorylist.msg
int32 page_num # Page number
int32 page_size # Size per page
int32 total_size # Length of the list +string vague_search # Fuzzy search
Trajectoryinfo[] tra_list # List of trajectories that match the criteria
bool state # Query status - true for success, false for failure| +| Return example | ros2 topic echo /rm_driver/get_trajectory_file_list_result | + +#### Start_Running_Specified_Trajectory + +| Function description | Start_Running_Specified_Trajectory | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::String | +| Command example | ros2 topic pub --once /rm_driver/set_run_trajectory_cmd std_msgs/msg/String "data: 'sss'" | +| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. | +| Return example | ros2 topic echo /rm_driver/set_run_trajectory_result | + +#### Delete_Specified_Trajectory_File + +| Function description | Delete_Specified_Trajectory_File | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::String | +| Command example | ros2 topic pub --once /rm_driver/delete_trajectory_file_cmd std_msgs/msg/String "data: 'sss'" | +| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. | +| Return example | ros2 topic echo /rm_driver/delete_trajectory_file_result | + +#### Save_Trajectory_File + +| Function description | Save_Trajectory_File | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::String | +| Command example | ros2 topic pub --once /rm_driver/save_trajectory_file_cmd std_msgs/msg/String "data: 'test'" | +| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. | +| Return example | ros2 topic echo /rm_driver/save_trajectory_file_result | + +#### Query_Flowchart_Program_Run_State + +| Function description | Query_Flowchart_Program_Run_State | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub --once /rm_driver/get_flowchart_program_run_state_cmd std_msgs/msg/Empty "{}" | +| Return value | Flowchartrunstate.msg
int run_state; #Running Status 0 Not Started 1 Running 2 Paused
int id;#The current enabled file ID.
char name[32];#The name of the currently enabled file.
int plan_speed;#The current enabled file global planning speed ratio is 1-100.
int step_mode;#Single step mode, 0 is empty, 1 is normal, and 2 is single step.
char modal_id[50];#The ID of the flowchart block that has been run. If it has not been run, no return will be sent. | +| Return example | ros2 topic echo /rm_driver/get_flowchart_program_run_state_result | + +### Modbus_Configuration + +#### Set_Controller_RS485_Mode + +| Function description | Set_Controller_RS485_Mode | +| :---: | :---- | +| Parameter description | RS485params.msg
int32 mode: 0-RS485 serial communication, 1-modbus RTU master mode, 2-Modbus RTU slave mode.
Int32 baudrate: Currently supports 9600 19200 38400 57600 115200 230400 460800. | +| Command example | ros2 topic pub /rm_driver/set_controller_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_controller_rs485_mode_result | + +#### Get_Controller_RS485_Mode + +| Function description | Get_Controller_RS485_Mode | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driv/get_controller_rs485_mode_cmd std_msgs/msg/Empty "{}" | +| Return value | RS485params.msg
int32 mode: 0-RS485 serial communication, 1-modbus RTU master mode, 2-Modbus RTU slave mode.
Int32 baudrate: Currently supports 9600 19200 38400 57600 115200 230400 460800. | +| Return example | ros2 topic echo /rm_driver/get_controller_rs485_mode_result | + +#### Set_Tool_End_RS485_Mode + +| Function description | Set_Tool_End_RS485_Mode | +| :---: | :---- | +| Parameter description | RS485params.msg
int32 mode: 0- Set the RS485 port of the tool end to RTU master station, 1- Smart hand mode, 2- Claw mode.
Int32 baudrate: Currently supports 9600 115200 460800. | +| Command example | ros2 topic pub --once /rm_driver/set_tool_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_tool_rs485_mode_result | + +#### Get_Tool_End_RS485_Mode + +| Function description | Get_Tool_End_RS485_Mode | +| :---: | :---- | +| Parameter description | ROS msg std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/get_tool_rs485_mode_cmd std_msgs/msg/Empty "{}" | +| Return value | RS485params.msg
int32 mode: 0- Set the RS485 port of the tool end to RTU master station, 1- Smart hand mode, 2- Claw mode.
Int32 baudrate: Currently supports 9600 115200 460800. | +| Return example | ros2 topic echo /rm_driver/get_tool_rs485_mode_result | + +### ModbusTCP_Master + +#### Add_Modbus_TCP_Master + +| Function description | Add_Modbus_TCP_Master | +| :---: | :---- | +| Parameter description | Modbustcpmasterinfo.msg
string master_name: Modbus master station name.
String ip: TCP master IP address.
Int32 port: TCP primary port number. | +| Command example | ros2 topic pub /rm_driver/add_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',ip: '127.0.0.1',port: 502}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/add_modbus_tcp_master_result | + +#### Update_Modbus_TCP_Master + +| Function description | Update_Modbus_TCP_Master | +| :---: | :---- | +| Parameter description | Modbustcpmasterinfo.msg
string master_name: Modbus old master station name.
string new_master_name: Modbus new master station name.
String ip: TCP master IP address.
Int32 port: TCP primary port number. | +| Command example | ros2 topic pub /rm_driver/update_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterupdata "{"master_name: '1',new_master_name: '125',ip: '127.0.0.1',port: 502"}" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/update_modbus_tcp_master_result | + +#### Delete_Modbus_TCP_Master + +| Function description | Delete_Modbus_TCP_Master | +| :---: | :---- | +| Parameter description | Mastername.msg
string master_name: Modbus master station name. | +| Command example | ros2 topic pub /rm_driver/delete_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" | +| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/delete_modbus_tcp_master_result | + +#### Get_Specified_Modbus_TCP_Master + +| Function description | Get_Specified_Modbus_TCP_Master | +| :---: | :---- | +| Parameter description | Mastername.msg
string master_name: Modbus master station name. | +| Command example | ros2 topic pub /rm_driver/get_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" | +| Return value | Modbustcpmasterinfo.msg
string master_name # Name of the Modbus master station, with a maximum length of 15 characters, not exceeding 15 characters
string ip # IP address of the TCP master station
int32 port # Port number of the TCP master station
bool state # Query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/get_modbus_tcp_master_result | + +#### Get_Modbus_TCP_Master_List + +| Function description | Get_Modbus_TCP_Master_List | +| :---: | :---- | +| Parameter description | Getmodbustcpmasterlist.msg
int32 page_num: Page number.
Int32 page_size: The size of each page.
String vague_search: Fuzzy search, returns a list of all main sites if the input is empty. | +| Command example | ros2 topic pub /rm_driver/get_modbus_tcp_master_list_cmd rm_ros_interfaces/msg/Getmodbustcpmasterlist "{page_num: 1,page_size: 10,vague_search: '1'}" | +| Return value | Modbustcpmasterlist.msg
uint8 page_num # Page number
uint8 page_size # Size per page
uint8 total_size # Length of the list
string vague_search # Fuzzy search
Modbustcpmasterinfo[] master_list # List of TCP master stations that match the criteria
bool state # Query status - true for success, false for failure
On failure, the driver terminal returns an error code | +| Return example | ros2 topic echo /rm_driver/get_modbus_tcp_master_list_result | + +### Tool_end_controller_end_RTU_Modbus_protocol_reads_and_writes_data + +#### Modbus_RTU_Protocol_Read_Coils + +| Function description | Modbus_RTU_Protocol_Read_Coils | +| :---: | :---- | +| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The number of data to be read, with a length not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code.| +| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_coils_result | + +#### Modbus_RTU_Protocol_Write_Coils + +| Function description | Modbus_RTU_Protocol_Write_Coils | +| :---: | :---- | +| Parameter description | Modbusrtuwriteparams.msg
int32 address: data starting address.
Int32 device: Address of peripheral device.
Int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host.
Int32 num: The maximum number of data to be written is 100.
Int32 [] data: The data to be written, with a length corresponding to num. | +| Command example | ros2 topic pub /rm_driver/write_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/write_modbus_rtu_coils_result | + +#### Modbus_RTU_Protocol_Read_Discrete_Inputs + +| Function description | Modbus_RTU_Protocol_Read_Discrete_Inputs | +| :---: | :---- | +| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host.
Int32 num: The number of data to be read, with a data length not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_input_status_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_input_status_result | + +#### Modbus_RTU_Protocol_Read_Holding_Registers + +| Function description | Modbus_RTU_Protocol_Read_Discrete_Inputs | +| :---: | :---- | +| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The number of data to be read, with a data length not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_holding_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # The data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_holding_registers_result | + +#### Modbus_RTU_Protocol_Write_Holding_Registers + +| Function description | Modbus_RTU_Protocol_Write_Holding_Registers | +| :---: | :---- | +| Parameter description | Modbusrtuwritableparams.msg
int32 address: data starting address
int32 device: peripheral device address
int32 type: 0-controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The maximum amount of data to be written, not exceeding 100
int32 [] data: The data to be written, with a length corresponding to num. | +| Command example | ros2 topic pub /rm_driver/write_modbus_rtu_registers_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/write_modbus_rtu_registers_result | + +#### Modbus_RTU_Protocol_Read_Input_Registers + +| Function description | Modbus_RTU_Protocol_Read_Input_Registers | +| :---: | :---- | +| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host..
Int32 num: The number of data to be read, with a data length not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_input_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_input_registers_result | + +### Controller_Modbus_TCP_protocol_reads_and_writes_data + +#### Modbus_TCP_Protocol_Read_Coils + +| Function description | Modbus_TCP_Protocol_Read_Coils | +| :---: | :---- | +| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_coils_result | + +#### Modbus_TCP_Protocol_Write_Coils + +| Function description | Modbus_TCP_Protocol_Write_Coils | +| :---: | :---- | +| Parameter description | Modbustcpwriteparames.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Write data quantity, maximum not exceeding 100.
Int32 [] data: The written data has a length corresponding to num. | +| Command example | ros2 topic pub /rm_driver/write_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/write_modbus_tcp_coils_result | + +#### Modbus_TCP_Protocol_Read_Discrete_Inputs + +| Function description | Modbus_TCP_Protocol_Read_Discrete_Inputs | +| :---: | :---- | +| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_input_status_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_input_status_result | + +#### Modbus_TCP_Protocol_Read_Holding_Registers + +| Function description | Modbus_TCP_Protocol_Read_Holding_Registers | +| :---: | :---- | +| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_holding_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_holding_registers_result | + +#### Modbus_TCP_Protocol_Write_Holding_Registers + +| Function description | Modbus_TCP_Protocol_Write_Holding_Registers | +| :---: | :---- | +| Parameter description | Modbustcpwriteparames.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Write data quantity, maximum not exceeding 100.
Int32 [] data: The written data has a length corresponding to num. | +| Command example | ros2 topic pub /rm_driver/write_modbus_tcp_registers_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/write_modbus_tcp_registers_result | + +#### Modbus_TCP_Protocol_Read_Input_Registers + +| Function description | Modbus_TCP_Protocol_Read_Input_Registers | +| :---: | :---- | +| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. | +| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_input_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_input_registers_result | + +### Functions_related_to_the_IO_configuration_of_the_end_tool + +#### Setting_the_tool_voltage_output + +| Function description | Setting the tool voltage output | +| :---: | :---- | +| Parameter description | ROS msg: std_msgs::msg::UInt16
uint16 data: power output type, range:0~3 0-0V,1-5V,2-12V,3-24V | +| Command example | ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_tool_voltage_result | + +### Functions_related_to_the_control_of_the_end_gripper + +The RealMan robotic arm is equipped with an Inspire Robots EG2-4C2 gripper. The robotic arm controller has made the gripper's ROS control mode available to the user to facilitate user operation. + +#### Setting_the_Gripper_Pick + +| Function description | Setting the gripper pick | +| :---: | :---- | +| Parameter description | Gripperpick.msg
uint16 speed: 1~1000,representing the opening and closing speed of the gripper, dimensionless.
uint16 force:representing the gripping force of the gripper, maximum 1.5 kg.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_gripper_pick_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_gripper_pick_result | + +#### Setting_the_gripper_pick-on + +| Function description | Setting the gripper pick-on | +| :---: | :---- | +| Parameter description | Gripperpick.msg
uint16 speed: 1~1000, representing the opening and closing speed of the gripper, dimensionless.
uint16 force: 1~1000,representing the gripping force of the gripper, maximum 1.5 kg.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_gripper_pick_on_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_gripper_pick_on_result | + +#### Setting_the_gripper_to_the_given_position + +| Function description | Setting the gripper to the given position | +| :---: | :---- | +| Parameter description | Gripperset.msg
uint16 position: target position of the gripper, range: 1-1000, representing the opening degree of the gripper: 0-70 mm.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500
block: true
timeout: 1000" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_gripper_position_result | + +### Functions_related_to_the_drag_teach_and_trajectory_reproduction + +#### Set_the_force-position_mixing_control + +| Function description | Set the force-position mixing control | +| :---: | :---- | +| Parameter description | Setforceposition.msg
uint8 sensor: 0 - One-axis force; 1 - Six-axis force
uint8 mode: 0 - Base coordinate system force control; 1 - Tool coordinate system force control
uint8 direction:Force control direction; 0 - Along the X-axis; 1 - Along the Y-axis; 2 - Along the Z-axis; 3 - Along the RX posture direction; 4 - Along the RY posture direction; 5 - Along the RZ posture direction
int16 n: The value of force, unit: N, accuracy: 0.1N | +| Command example | ros2 topic pub --once /rm_driver/set_force_postion_cmd rm_ros_interfaces/msg/Setforceposition "sensor: 1
mode: 0
direction: 2
n: 3" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_force_postion_result | + +#### Stop_the_force-position_mixing_control + +| Function description | Stop the force-position mixing control | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/clear_force_data_result | + +### Functions_related_to_the_use_of_six-axis_force_sensors_at_the_end + +The RealMan RM-65F robotic arm has an integrated six-axis force sensor at the end without external wiring. Users can operate the six-axis force through ROS topics. + +#### Query_the_six-axis_force_data + +| Function description | Query the six-axis force data| +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub rm_driver/get_force_data_cmd std_msgs/msg/Empty "{}" | +| Return value | Successfully returned six-axis force data in the corresponding coordinate system. | +| Return example | ros2 topic echo /rm_driver/get_force_data_result displays the raw force data.
ros2 topic echo /rm_driver/get_zero_force_data_result displays the system force data.
ros2 topic echo /rm_driver/get_work_force_data_result displays the force data in the work coordinate system.
ros2 topic echo /rm_driver/get_tool_force_data_result displays the force data in the tool coordinate system. | + +#### Clearing_the_six-axis_force_Data + +| Function description | Clearing the six-axis force data | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty| +| Command example | ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/clear_force_data_result | + +### Functions_related_to_the_control_of_the_five-finger_dexterous_hand + +The RealMan RM-65 robotic arm has been equipped with a five-finger dexterous hand at the end. Users can set the hand through the ROS. + +#### Setting_the_serial_number_of_the_dexterous_hand_posture + +| Function description | Setting the serial number of the dexterous hand posture | +| :---: | :---- | +| Parameter description | Handposture.msg
uint16 posture_num: the serial number of the posture pre-saved in the dexterous hand, ranging from 1 to 40.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking.
uint16 timeout: The timeout setting for blocking mode, unit: seconds. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_posture_cmd rm_ros_interfaces/msg/Handposture "posture_num: 1
block: true
timeout: 1000" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_posture_result | + +#### Set_the_dexterous_hand_action_sequence_number + +| Function description | Set the dexterous hand action sequence number | +| :---: | :---- | +| Parameter description | Handseq.msg
uint16 seq_num: the serial number of the action sequence pre-saved in the dexterous hand, ranging from 1 to 40.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking.
uint16 timeout: The timeout setting for blocking mode, unit: seconds. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_seq_cmd rm_ros_interfaces/msg/Handseq "seq_num: 1
block: true
timeout:1000" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_seq_result | + +#### Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand + +| Function description | Setting the angles of various degrees of freedom for the dexterous hand | +| :---: | :---- | +| Parameter description | Handangle.msg
int16[6] hand_angle: hand angle array, the range is 0 to 1000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_angle_result | + +#### Setting_the_dexterous_hand_speed + +| Function description | Setting the dexterous hand speed | +| :---: | :---- | +| Parameter description | Handspeed.msg
uint16 hand_speed: hand speed, range: 1-1000. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_speed_cmd rm_ros_interfaces/msg/Handspeed "hand_speed: 200" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_speed_result | + +#### Setting_the_force_threshold_of_the_dexterous_hand + +| Function description | Setting the force threshold of the dexterous hand | +| :---: | :---- | +| Parameter description | Handforce.msg
uint16 hand_force: hand force, range: 1-1000. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_force_cmd rm_ros_interfaces/msg/Handforce "hand_force: 200" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_force_result | + +#### Setting_the_angle_following_of_the_dexterous_hand + +| Function description | Setting the angle following of the dexterous hand | +| :---: | :---- | +| Parameter description | Handangle.msg
int16[6] hand_angle: hand angle array, the range is 0 to 2000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_follow_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_follow_angle_result | + +#### Setting_the_posture_following_of_the_dexterous_hand + +| Function description | Setting the posture following of the dexterous hand | +| :---: | :---- | +| Parameter description | Handangle.msg
int16[6] hand_angle: hand posture array, the range is 0 to 1000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_hand_follow_pos_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_hand_follow_pos_result | + +### Lifting_mechanism + +The RealMan robotic arm can be integrated with the self-developed lifting mechanism. + +#### Speed_open-loop_control_of_the_lifting_mechanism + +| Function description | Speed open-loop control of the lifting mechanism | +| :---: | :---- | +| Parameter description | Liftspeed.msg
int16 speed: speed percentage, -100-100, Speed < 0: the lifting mechanism moves downward, Speed > 0: the lifting mechanism moves upward, Speed = 0: the lifting mechanism stops.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_lift_speed_result | + +#### Position_closed-loop_control_of_the_lifting_mechanism + +| Function description | Position closed-loop control of the lifting mechanism | +| :---: | :---- | +| Parameter description | Liftheight.msg
uint16 height: target height, unit: mm, range: 0-2600.
uint16 speed: speed percentage, 1-100.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. | +| Command example | ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0
speed: 10
block: true" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_lift_height_result | + +#### Get_the_lifting_mechanism_state + +| Function description | Get the lifting mechanism state | +| :---: | :---- | +| Parameter description | Liftstate.msg
int16 height: current height.
int16 current: current current.
uint16 err_flag: drive error code. | +| Command example | ros2 topic pub /rm_driver/get_lift_state_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: current state of the lifting mechanism; Failure return: the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/get_lift_state_result | + +### End_Effector_Ecosystem_Command_Set + +Reading of basic and real-time information of end-effector devices supported by the end-effector ecosystem protocol. + +#### Setting_End_Effector_Ecosystem_Protocol_Mode + +| Function description | Set End-Effector Ecosystem Protocol Mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Int32
0 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800). | +| Command example | ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_rm_plus_mode_result | + +#### Querying_End_Effector_Ecosystem_Protocol_Mode + +| Function description | Querying End-Effector Ecosystem Protocol Mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" | +| Return value | 0 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800). | +| Return example | ros2 topic echo /rm_driver/get_rm_plus_mode_result | + +#### Setting Tactile Sensor Mode + +| Function description | Setting Tactile Sensor Mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Int32
0 - Disable tactile sensor;
1 - Enable tactile sensor (returns processed data);
2 - Enable tactile sensor (returns raw data). | +| Command example | ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_rm_plus_touch_result | + +#### Querying_Tactile_Sensor_Mode + +| Function description | Querying_Tactile_Sensor_Mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" | +| Return value | std_msgs::msg::Int32
0 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800). | +| Return example | ros2 topic echo /rm_driver/get_rm_plus_mode_result | + +### Functions_related_to_the_transmissive_force-position_compensation_Mode + +For the RealMan robotic arm with one-axis force and six-axis force versions, the user can not only directly use the teaching device to call the underlying force-position mixing control module but also combine the custom trajectory with the underlying force-position mixing control algorithm in the form of periodic transmission to compensate. +If force data calibration has not been completed before the force operations, the zero position can be calibrated using the one-axis force and six-axis force data clear interfaces. + +#### Starting_the_transmissive_force-position_mixing_control_compensation_mode + +| Function description | starting the transmissive force-position mixing control compensation mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/start_force_position_move_result | + +#### Stopping_the_transmissive_force-position_mixing_control_compensation_mode + +| Function description | Stopping the transmissive force-position mixing control compensation mode | +| :---: | :---- | +| Parameter description | std_msgs::msg::Empty | +| Command example | ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/stop_force_position_move_result | + +#### Transmissive_force-position_mixing_control_compensation-joint + +| Function description | Transmissive force-position mixing control compensation (joint) | +| :---: | :---- | +| Parameter description | Forcepositionmovejoint.msg
float32[6] joint: target joint radian
uint8 sensor: type of sensor used, 0 - one-axis force, 1 - six-axis force
uint8 mode, 0 - along the base coordinate system, 1 - along the tool coordinate system.
int16 dir: force control direction, 0-5 represent X/Y/Z/Rx/Ry/Rz respectively, where the default direction is Z direction for one-axis force type
float32 force: force value, unit: 0.1 N.
bool follow: whether high follow, true: high follow, false: low follow.
uint8 dof:degree of freedom of the robotic arm | +| Command example | It needs to be a large number (10 or more) of continuous position points, with more than 2ms period continuous release.
ros2 topic pub /rm_driver/force_position_move_joint_cmd rm_ros_interfaces/msg/Forcepositionmovejoint " joint: [0, 0, 0, 0, 0, 0]
sensor: 0
mode: 0
dir: 0
force: 0.0
follow: false
dof: 6 | +| Return value | Success: no return; Failure return: false, and the driver terminal returns an error code. | + +#### Transmissive_force-position_mixing_control_compensation-pose + +| Function description | Transmissive force-position mixing control compensation (pose) | +| :---: | :---- | +| Parameter description | Forcepositionmovepose.msg
geometry_msgs/Pose pose: target pose, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 sensor: type of sensor used, 0 - one-axis force, 1 - six-axis force.
uint8 mode: mode, 0 - along the base coordinate system, 1 - along the tool coordinate system
int16 dir: force control direction, 0-5 represent X/Y/Z/Rx/Ry/Rz respectively, where the default direction is Z direction for one-axis force type.
float32 force: force value,unit:0.1 N.
bool follow: whether high follow, true: high follow, false: low follow. | +| Command example | It needs to be a large number (10 or more) of continuous position points, with more than 2ms period continuous release.
ros2 topic pub /rm_driver/force_position_move_pose_cmd rm_ros_interfaces/msg/Forcepositionmovepose "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
sensor: 0
mode: 0
dir: 0
force: 0
follow: false" | +| Return value | Success: no return; Failure return: false, and the driver terminal returns an error code.| + +### Robotic_arm_state_active_reporting + +#### Setting_UDP_robotic_arm_state_active_reporting_configuration + +| Function description | Set UDP robotic arm state active reporting configuration | +| :---: | :---- | +| Parameter description | Setrealtimepush.msg
uint16 cycle: set the broadcast cycle, which is a multiple of 5ms (default 1 i.e. 1 * 5 = 5 ms, 200 Hz).
uint16 port: set the broadcast port number (default 8089).
uint16 force_coordinate: set the coordinate system of force data outside the system (only supported by the arm with force sensors).
string ip: set the custom reporting target IP address (default 192.168.1.10).
bool hand_enable: whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enable: whether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enable: whether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enable: whether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enable: whether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enable: whether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enable: Basic information of the end-effector device,true is enabled, and false is not enabled
plus_state_enable: Real-time information of the end-effector device,true is enabled, and false is not enabled. | +| Command example | ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1
port: 8089
force_coordinate: 0
ip: '192.168.1.10'
hand_enable: false
aloha_state_enable: false
arm_current_status_enable: false
expand_state_enable: false
joint_speed_enable: false
lift_state_enable: false" | +| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/set_realtime_push_result | + +#### Getting_UDP_robotic_arm_state_active_reporting_configuration + +| Function description | Get UDP robotic arm state active reporting configuration | +| :---: | :---- | +| Parameter description | Setrealtimepush.msg
uint16 cycle: set the broadcast cycle, which is a multiple of 5ms (default 1 i.e. 1 * 5 = 5 ms, 200 Hz).
uint16 port: set the broadcast port number (default 8089).
uint16 force_coordinate: set the coordinate system of force data outside the system (only supported by the arm with force sensors).
string ip: set the custom reporting target IP address (default 192.168.1.10).
bool hand_enable: whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enable: whether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enable: whether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enable: whether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enable: whether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enable: whether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enable: Basic information of the end-effector device,true is enabled, and false is not enabled
plus_state_enable: Real-time information of the end-effector device,true is enabled, and false is not enabled. | +| Command example | ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}" | +| Return value | Successfully set information; Failure return: the driver terminal returns an error code. | +| Return example | ros2 topic echo /rm_driver/get_realtime_push_result | + +#### UDP_robotic_arm_state_active_reporting + +* Six-axis force + +| Function description | Six-axis force | +| :---: | :---- | +| Parameter description | Sixforce.msg
float32 force_fx: the force along the x-axis direction.
float32 force_fy: the force along the y-axis direction.
float32 force_fz: the force along the z-axis direction.
float32 force_mx: the force when rotating along the x-axis direction.
float32 force_my: the force when rotating along the y-axis direction.
float32 force_mz: the force when rotating along the z-axis direction. | +| Subscription command | ros2 topic echo /rm_driver/udp_six_force | + +* One-axis force + +| Function description | One-axis force | +| :---: | :---- | +| Parameter description | Sixforce.msg
float32 force_fx: the force along the x-axis direction.
float32 force_fy: the force along the y-axis direction.
float32 force_fz: the force along the z-axis direction.(only this value is valid)
float32 force_mx: the force when rotating along the x-axis direction.
float32 force_my: the force when rotating along the y-axis direction.
float32 force_mz: the force when rotating along the z-axis direction. | +| Subscription command | ros2 topic echo /rm_driver/udp_one_force | + +* Robotic arm error + +| Function description | Robotic arm error | +| :---: | :---- | +| Parameter description | std_msgs::msg::UInt16
uint16 data: the robotic arm error message. | +| Subscription command | ros2 topic echo /rm_driver/udp_arm_err | + +* System error + +| Function description | System error | +| :---: | :---- | +| Parameter description | std_msgs::msg::UInt16
uint16 data: the system error message. | +| Subscription command | ros2 topic echo /rm_driver/udp_sys_err | + +* Joint error + +| Function description | Joint error | +| :---: | :---- | +| Parameter description | Jointerrorcode.msg
uint16[] joint_error: the error message for each joint.
Uint8 dof: the arm degree of freedom message. | +| Subscription command | ros2 topic echo /rm_driver/udp_joint_error_code | + +* The robot arm radians data + +| Function description | The robot arm radians data | +| :---: | :---- | +| Parameter description | sensor_msgs::msg::JointState
builtin_interfaces/Time stamp
int32 sec: time message, unit: second.
uint32 nanosec: time message, unit: nanosecond.
string frame_id: coordinate system name.
string[] name: joint name.
float64[] position: joint radian message.
float64[] velocity: joint speed message. (not used yet)
float64[] effort: joint force message. (not used yet) | +| Subscription command | ros2 topic echo /joint_states | + +* Pose information + +| Function description | Pose information | +| :---: | :---- | +| Parameter description | geometry_msgs::msg::Pose
Point position: the robotic arm current coordinate information.
float64 x
float64 y
float64 z
Quaternion orientation: the robotic arm current pose information.
float64 x 0
float64 y 0
float64 z 0
float64 w 1 | +| Subscription command | ros2 topic echo /rm_driver/udp_arm_position | + +* Current external force data of the six-axis force sensor system + +| Function description | Current external force data of the six-axis force sensor system | +| :---: | :---- | +| Parameter description | Sixforce.msg
float32 force_fx: the force forced on the current sensor along the x-axis direction.
float32 force_fy: the force forced on the current sensor along the y-axis direction.
float32 force_fz: the force forced on the current sensor along the z-axis direction.
float32 force_mx: the force forced on the current sensor when rotating along the x-axis direction.
float32 force_my: the force forced on the current sensor when rotating along the y-axis direction.
float32 force_mz: the force forced on the current sensor when rotating along the z-axis direction. | +| Subscription command | ros2 topic echo /rm_driver/udp_six_zero_force | + +* Current external force data of the one-axis force sensor system + +| Function description | Current external force data of the one-axis force sensor system | +| :---: | :---- | +| Parameter description | Sixforce.msg
float32 force_fx: the force forced on the current sensor along the x-axis direction.
float32 force_fy: the force forced on the current sensor along the y-axis direction.
float32 force_fz: the force forced on the current sensor along the z-axis direction. (only this data is valid)
float32 force_mx: the force forced on the current sensor when rotating along the x-axis direction.
float32 force_my: the force forced on the current sensor when rotating along the y-axis direction.
float32 force_mz: the force forced on the current sensor when rotating along the z-axis direction. | +| Subscription command | ros2 topic echo /rm_driver/udp_one_zero_force | + +* Reference coordinate system for external force data of the system + +| Function description | Reference coordinate system for external force data of the system | +| :----: | :---- | +| Parameter description | std_msgs::msg::UInt16
uint16 data: : coordinate system for external force data of the system, where 0 is the sensor coordinate system, 1 is the current work coordinate system, and 2 is the current tool coordinate system This data affects the reference coordinate system for external force data of one-axis and six axis force sensor systems. | +| Subscription command | ros2 topic echo /rm_driver/udp_arm_coordinate | + + +* The current state of dexterous dexterity + +| Function description | The current state of dexterous dexterity | +| :----: | :---- | +| Parameter description | rm_ros_interfaces::msg::Handstatus.msg
uint16[6] hand_angle: #Finger angle array,range: 0~2000.
uint16[6] hand_pos: #Finger position array,range: 0~1000.
uint16[6] hand_state: #Finger state,0 is releasing, 1 is grasping, 2 positions are in place and stop, 3 forces are in place and stop, 5 current protection stops, 6 electric cylinder stalling stops, 7 electric cylinder failure stops.
uint16[6] hand_force: #Dexterous hand degree of freedom current,unit mN.
uint16 hand_err: #Agile Hand System Error,1 indicates an error, 0 indicates no error. | +| Subscription command | ros2 topic echo /rm_driver/udp_hand_status | + +* current status of the mechanical arm + +| Function Description | Get the current status of the mechanical arm | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Armcurrentstatus.msg
uint16 arm_current_status: mechanical arm status
0-RM_IDLE_E // enabled but idle status
1-RM_MOVE_L_E // Move L moving state
2-RM_MOVE_J_E // move J moving state
3-RM_MOVE_C_E // move C moving state
4-RM_MOVE_S_E // move S moving state
5-RM_MOVE_THROUGH_JOINT_E /angle transmission state
6-RM_MOVE_THROUGH_POSE_E // posture transmission state
7-RM_MOVE_THROUGH_FORCE_POSE_E//force control transmission state
8-RM_MOVE_THROUGH_CURRENT_E// Current loop transparent state
9-RM_STOP_E // emergency stop state
10-RM_SLOW_STOP_E // slow stop state
11-RM_PAUSE_E // Pause state
12-RM_CURRENT_DRAG_E // Current loop drag state
13-RM_SENSOR_DRAG_E // Six-axis force drag state
14-RM_TECH_DEMONSTRATION_E//Teaching state | +| query example | ros2 topic echo /rm_driver/udp_arm_current_status | + +* Current joint current + +| Function Description | Current Joint Current | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointcurrent.msg
float 32 [] joint_current: current joint current with accuracy of 0.001mA | +| query example | ros2 topic echo /rm_driver/udp_joint_current | + +* The current joint enabling state + +| Function Description | Current Joint Enabling Status | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointenflag.msg
bool [] joint_en_flag: the current joint enabling state, where 1 is the upper enabling state and 0 is the lower enabling state | +| query example | ros2 topic echo /rm_driver/udp_joint_en_flag | + +* Euler angle posture of mechanical arm + +| Function Description | Euler Angle Pose of Mechanical Arm | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointposeeuler.msg
float 32 [3] Euler: Euler angle of current waypoint attitude with accuracy of 0.001rad
float32[3] position: current waypoint position with accuracy of 0.000001M| +| query example | ros2 topic echo /rm_driver/udp_joint_pose_Euler | + +* Current joint speed + +| Function Description | Current joint speed | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointspeed.msg
float 32 [] joint_speed: current joint speed with an accuracy of 0.02RPM. | +| query example | ros2 topic echo /rm_driver/udp_joint_speed | + +* Current joint temperature + +| Function Description | Current joint temperature | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointtemperature.msg
float 32 [] joint_temperature: current joint temperature with accuracy of 0.001℃| +| query example | ros2 topic echo /rm_driver/udp_joint_temperature | + +* Current joint voltage + +| Function Description | Current Joint Voltage | +| :----: | :---- | +| parameter description | rm_ros_interfaces:: msg:: Jointvoltage.msg
float 32 [] joint_voltage: current joint voltage with accuracy of 0.001V| +| query example | ros2 topic echo /rm_driver/udp_joint_voltage | + +* Reading Basic Information of End-Effector Device + +| Function Description | Reading Basic Information of End-Effector Device | +| :----: | :---- | +| parameter description | rm_ros_interfaces::msg::Rmplusbase.msg
string manu:Device manufacturer.
int8 type: Device type, including 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper
string hv:Hardware version
string sv:Software version
string bv:Bootloader version
int32 id:Device ID
int8 dof:Degrees of freedom
int8 check:Self-check switch
int8 bee:Beeper switch
bool force:Force control support
bool touch:Tactile support
int8 touch_num:Number of tactile sensors
int8 touch_sw:Tactile switch
int8 hand:Hand orientation, including 1 - Left hand, 2 - Right hand
int32[12] pos_up:Position upper limit
int32[12] pos_low:Position lower limit
int32[12] angle_up:Angle upper limit,Unit: 0.01 degrees.
int32[12] angle_low:Angle lower limit,Unit: 0.01 degrees.
int32[12] speed_up:Speed upper limit
int32[12] speed_low:Speed lower limit
int32[12] force_up:Force upper limit
int32[12] force_low:Force lower limit,Unit: 0.001N.| +| query example | ros2 topic echo /rm_driver/udp_rm_plus_base | + +* Reading Real-Time Information of End-Effector Device + +| Function Description | Reading Real-Time Information of End-Effector Device | +| :----: | :---- | +| parameter description | rm_ros_interfaces::msg::Rmplusstate.msg
int32 sys_state:System status.
int32[12] dof_state:Current status of each degree of freedom (DoF)
int32[12] dof_err:Error information of each DoF
int32[12] pos: Current position of each DoF
int32[12] speed:Current speed of each DoF
int32[12] angle:Current Angle of Each Degree of Freedom angle,Unit: 0.01 degrees.
int32[12] current:Current of each DoF,Unit: mA.
int32[18] normal_force:Normal force of the tactile three-dimensional force of each DoF
int32[18] tangential_force:Tangential force of the tactile three-dimensional force of each DoF
int32[18] tangential_force_dir:Direction of the tangential force of the tactile three-dimensional force of each DoF
uint32[12] tsa:Tactile self-approach of each DoF
uint32[12] tma:Tactile mutual approach of each DoF
int32[18] touch_data:Raw data from the tactile sensor
int32[12] force:Torque of each DoF,Unit: 0.001N.| +| query example | ros2 topic echo /rm_driver/udp_rm_plus_state | diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png new file mode 100755 index 0000000..8090991 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png new file mode 100755 index 0000000..0d5bfd3 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png new file mode 100755 index 0000000..9ac9087 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png new file mode 100755 index 0000000..dcfd810 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md new file mode 100755 index 0000000..e7803ac --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md @@ -0,0 +1,937 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md) + +
+ +
+ +# 睿尔曼机械臂接口函数说明(ROS2)V1.1.6 + + + + + +睿尔曼智能科技(北京)有限公司 + +文件修订记录: + +|版本号 | 时间 | 备注 | +| :---: | :---- | :---: | +|V1.0 | 2024-2-18 | 拟制 | +|V1.1 | 2024-7-8 | 修订(添加示教指令3.6) | +|V1.1.1| 2024-8-13| 修订(添加查询六维力数据)| +|V1.1.2| 2024-9-25| 修订(修正坐标系话题描述错误)| +|V1.1.3| 2024-10-31|修订(添加灵巧手UDP功能,跟随功能)| +|V1.1.4| 2024-12-25|修订(修改UDP上报内容)| +|V1.1.5| 2025-02-19|修订(适配API2、添加末端生态协议接口、更新UDP接口)| +|V1.1.6| 2025-05-19|修订(适配四代控制器、添加版本查询接口、添加笛卡尔空间直线偏移运动接口、添加Modbus接口、添加轨迹列表接口)| + + +
+ +## 目录 +* 1[简介](#简介) +* 2[报错说明](#报错说明) +* 2.1[控制器错误类型](#控制器错误类型) +* 2.2[关节错误类型](#关节错误类型) +* 2.3[API错误类型](#API错误类型) +* 3[ROS功能包机械臂相关指令使用说明](#ROS功能包机械臂相关指令使用说明) +* 3.1[关节配置](#关节配置) +* 3.1.1[清除关节错误代码](#清除关节错误代码) +* 3.2[版本查询](#版本查询) +* 3.2.1[查询机械臂基本信息](#查询机械臂基本信息) +* 3.2.2[查询机械臂软件版本](#查询机械臂软件版本) +* 3.2.3[查询关节软件版本](#查询关节软件版本) +* 3.2.4[查询末端接口板软件版本号](#查询末端接口板软件版本号) +* 3.3[工作坐标系设置](#工作坐标系设置) +* 3.3.1[切换当前工作坐标系](#切换当前工作坐标系) +* 3.4[坐标系查询](#坐标系查询) +* 3.4.1[查询当前工具坐标系](#查询当前工具坐标系) +* 3.4.2[查询所有工具坐标系名称](#查询所有工具坐标系名称) +* 3.4.3[查询当前工作坐标系](#查询当前工作坐标系) +* 3.4.4[查询所有工作坐标系](#查询所有工作坐标系) +* 3.5[机械臂状态查询](#机械臂状态查询) +* 3.5.1[获取机械臂当前状态-返回关节角度+欧拉角](#获取机械臂当前状态-返回各关节角度和欧拉角) +* 3.5.2[获取机械臂当前状态-返回各关节弧度+四元数](#获取机械臂当前状态-返回各关节弧度和四元数) +* 3.6[机械臂运动规划](#机械臂运动规划) +* 3.6.1[关节空间运动](#关节空间运动) +* 3.6.2[笛卡尔空间直线运动](#笛卡尔空间直线运动) +* 3.6.3[笛卡尔空间直线偏移运动](#笛卡尔空间直线偏移运动) +* 3.6.4[笛卡尔空间圆弧运动](#笛卡尔空间圆弧运动) +* 3.6.5[关节角度CANFD透传](#关节角度CANFD透传) +* 3.6.6[自定义高跟随模式关节角度CANFD透传](#自定义高跟随关节角度CANFD透传) +* 3.6.7[位姿CANFD透传](#位姿CANFD透传) +* 3.6.8[自定义高跟随模式位姿CANFD透传](#自定义高跟随模式位姿CANFD透传) +* 3.6.9[关节空间规划到目标位姿](#关节空间规划到目标位姿) +* 3.6.10[轨迹急停](#轨迹急停) +* 3.6.11[紧急停止](#紧急停止) +* 3.7[示教指令](#示教指令) +* 3.7.1[关节示教](#关节示教) +* 3.7.2[位置示教](#位置示教) +* 3.7.3[姿态示教](#姿态示教) +* 3.7.4[示教停止](#示教停止) +* 3.8[轨迹列表](#轨迹列表) +* 3.8.1[查询轨迹列表](#查询轨迹列表) +* 3.8.2[开始运行指定轨迹](#开始运行指定轨迹) +* 3.8.3[删除指定轨迹文件](#删除指定轨迹文件) +* 3.8.4[保存轨迹文件](#保存轨迹文件) +* 3.8.5[查询流程图编程状态](#查询流程图编程状态) +* 3.9[Modbus模式查询与配置](#Modbus模式查询与配置) +* 3.9.1[配置控制器通讯端口RS485模式](#配置控制器通讯端口RS485模式) +* 3.9.2[查询控制器RS485模式](#查询控制器RS485模式) +* 3.9.3[配置工具端RS485模式](#配置工具端RS485模式) +* 3.9.4[查询工具端RS485模式](#查询工具端RS485模式) +* 3.10[ModbusTCP主站](#ModbusTCP主站) +* 3.10.1[新增Modbus TCP主站](#新增ModbusTCP主站) +* 3.10.2[更新Modbus TCP主站](#更新ModbusTCP主站) +* 3.10.3[删除Modbus TCP主站](#删除ModbusTCP主站) +* 3.10.4[查询指定Modbus主站](#查询指定Modbus主站) +* 3.10.5[查询Modbus主站列表](#查询Modbus主站列表) +* 3.11[工具端控制器端RTU Modbus协议读写数据](#工具端控制器端ModbusRTU协议读写数据) +* 3.11.1[ModbusRTU协议读线圈](#ModbusRTU协议读线圈) +* 3.11.2[ModbusRTU协议写线圈](#ModbusRTU协议写线圈) +* 3.11.3[ModbusRTU协议读离散量输入](#ModbusRTU协议读离散量输入) +* 3.11.4[ModbusRTU协议读保持寄存器](#ModbusRTU协议读保持寄存器) +* 3.11.5[ModbusRTU协议写保持寄存器](#ModbusRTU协议写保持寄存器) +* 3.11.6[ModbusRTU协议读输入寄存器](#ModbusRTU协议读输入寄存器) +* 3.12[控制器ModbusTCP协议读写数据](#控制器ModbusTCP协议读写数据) +* 3.12.1[ModbusTCP协议读线圈](#ModbusTCP协议读线圈) +* 3.12.2[ModbusTCP协议写线圈](#ModbusTCP协议写线圈) +* 3.12.3[ModbusTCP协议读离散量输入](#ModbusTCP协议读离散量输入) +* 3.12.4[ModbusTCP协议读保持寄存器](#ModbusTCP协议读保持寄存器) +* 3.12.5[ModbusTCP协议写保持寄存器](#ModbusTCP协议写保持寄存器) +* 3.12.5[ModbusTCP协议读输入寄存器](#ModbusTCP协议读输入寄存器) +* 3.13[末端工具IO配置](#末端工具IO配置) +* 3.13.1[设置工具端电源输出](#设置工具端电源输出) +* 3.14[末端手爪控制](#末端手爪控制) +* 3.14.1[设置夹爪力控夹取](#设置夹爪力控夹取) +* 3.14.2[设置夹爪持续力控夹取](#设置夹爪持续力控夹取) +* 3.14.3[夹爪到达指定位置](#夹爪到达指定位置) +* 3.15[拖动示教及轨迹复现](#拖动示教及轨迹复现) +* 3.15.1[设置力位混合控制](#设置力位混合控制) +* 3.15.2[结束力位混合控制](#结束力位混合控制) +* 3.16[末端六维力传感器的使用](#末端六维力传感器的使用) +* 3.16.1[查询六维力数据](#查询六维力数据) +* 3.16.2[清空六维力数据](#清空六维力数据) +* 3.17[末端五指灵巧手控制](#末端五指灵巧手控制) +* 3.17.1[设置灵巧手手势序号](#设置灵巧手手势序号) +* 3.17.2[设置灵巧手动作序列](#设置灵巧手动作序列) +* 3.17.3[设置灵巧手各自由度角度](#设置灵巧手各自由度角度) +* 3.17.4[设置灵巧手速度](#设置灵巧手速度) +* 3.17.5[设置灵巧手力阈值](#设置灵巧手力阈值) +* 3.17.6[设置灵巧手角度跟随](#设置灵巧手角度跟随) +* 3.17.7[设置灵巧手姿态跟随](#设置灵巧手姿态跟随) +* 3.18[升降机构](#升降机构) +* 3.18.1[升降机构速度开环控制](#升降机构速度开环控制) +* 3.18.2[升降机构位置闭环控制](#升降机构位置闭环控制) +* 3.18.3[获取升降机构状态](#获取升降机构状态) +* 3.19[末端生态协议](#末端生态协议) +* 3.19.1[设置末端生态协议模式](#设置末端生态协议模式) +* 3.19.2[查询末端生态协议模式](#查询末端生态协议模式) +* 3.19.3[设置触觉传感器模式](#设置触觉传感器模式) +* 3.19.4[获取触觉传感器模式](#获取触觉传感器模式) +* 3.20[透传力位混合控制补偿](#透传力位混合控制补偿) +* 3.20.1[开启透传力位混合控制补偿模式](#开启透传力位混合控制补偿模式) +* 3.20.2[关闭透传力位混合控制补偿模式](#关闭透传力位混合控制补偿模式) +* 3.20.3[透传力位混合补偿-关节](#透传力位混合补偿-关节) +* 3.20.4[透传力位混合补偿-位姿](#透传力位混合补偿-位姿) +* 3.21[机械臂状态主动上报](#机械臂状态主动上报) +* 3.21.1[设置UDP机械臂状态主动上报配置](#设置UDP机械臂状态主动上报配置) +* 3.21.2[查询UDP机械臂状态主动上报配置](#查询UDP机械臂状态主动上报配置) +* 3.21.3[UDP机械臂状态主动上报](#UDP机械臂状态主动上报) + +  +## 简介 +为了方便用户通过ROS2控制机械臂,睿尔曼提供了基于API的ROS2功能包,有关机械臂的控制细节想要了解的话也可以参考API的相关文档和说明,在实际使用机械臂时,用户可通过以太网口与机械臂建立通信,并控制机械臂。 +## 报错说明 +### 控制器错误类型 +| 序号 | 错误代码(16进制) | 错误内容 | +| :---: | :---- | :---: | +| 1 | 0x0000 | 系统正常 | +| 2 | 0x1001 | 关节通信异常 | +| 3 | 0x1002 | 目标角度超过限位 | +| 4 | 0x1003 | 该处不可达,为奇异点 | +| 5 | 0x1004 | 实时内核通信错误 | +| 6 | 0x1005 | 关节通信总线错误 | +| 7 | 0x1006 | 规划层内核错误 | +| 8 | 0x1007 | 关节超速 | +| 9 | 0x1008 | 末端接口板无法连接 | +| 10 | 0x1009 | 超速度限制 | +| 11 | 0x100A | 超加速度限制 | +| 12 | 0x100B | 关节抱闸未打开 | +| 13 | 0x100C | 拖动示教时超速 | +| 14 | 0x100D | 机械臂发生碰撞 | +| 15 | 0x100E | 无该工作坐标系 | +| 16 | 0x100F | 无该工具坐标系 | +| 17 | 0x1010 | 关节发生掉使能错误 | +### 关节错误类型 + +| 序号 | 错误代码(16进制) | 错误内容 | +| :---: | :---- | :---: | +| 1 | 0x0000 | 关节正常 | +| 2 | 0x0001 | FOC错误 | +| 3 | 0x0002 | 过压 | +| 4 | 0x0004 | 欠压 | +| 5 | 0x0008 | 过温 | +| 6 | 0x0010 | 启动失败 | +| 7 | 0x0020 | 编码器错误 | +| 8 | 0x0040 | 过流 | +| 9 | 0x0080 | 软件错误 | +| 10 | 0x0100 | 温度传感器错误 | +| 11 | 0x0200 | 位置超限错误 | +| 12 | 0x0400 | 关节ID非法 | +| 13 | 0x0800 | 位置跟踪错误 | +| 14 | 0x1000 | 电流检测错误 | +| 15 | 0x2000 | 抱闸打开失败 | +| 16 | 0x4000 | 位置指令阶跃警告 | +| 17 | 0x8000 | 多圈关节丢圈数 | +| 18 | 0xF000 | 通信丢帧 | +### API错误类型 + +| 错误代码(int) | 说明 | 处理建议 | +| :---: | :---- | :--- | +| 0 | 系统运行正常 | - | +| 1 | 消息请求返回FALSE | - 校验JSON指令:
①启用API的DEBUG日志,捕获原始JSON数据。
②检查JSON语法:确保括号、引号、逗号等格式正确(可借助JSON校验工具)。
③对照API文档,验证参数名称、数据类型及取值范围是否符合规范。
④修正问题后重新发送指令,检查控制器返回的状态码及业务数据是否正常。
- 检查机械臂状态:
①查看机械臂控制器或日志中的实时报错信息(如硬件故障、超限等),根据提示复位、校准或排查硬件问题。
②修正问题后重新发送指令,检查控制器返回的状态码及业务数据是否正常。| +| -1 | 数据发送失败,通信过程中出现问题 | 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。| +| -2 | 数据接收失败,通信过程中出现问题或者控制器超时没有返回。|- 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。
- 校验版本兼容性:
①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考版本变更说明。
②若版本过低需升级控制器或使用适配的API版本。
- 调用ModbusTCP接口:仅在读写控制器ModbusTCP设备时适用,创建机械臂控制句柄后,必须调用rm_set_modbustcp_mode()接口,否则无法接收到返回值。| +| -3 | 返回值解析失败,接收到的数据格式不正确或不完整。|校验版本兼容性:
①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考[版本变更说明](#https://develop.realman-robotics.com/robot/releaseNotes/releaseNotes/)。
②若版本过低需升级控制器或使用适配的API版本。| +| -4 | 当前到位设备校验失败,即当前到位设备不为关节/升降机构/夹爪/灵巧手。| - 检测多设备并发控制:检查是否有其他设备给机械臂发送运动指令:包括机械臂、夹爪、灵巧手、升降机的运动;
- 实时监听指令事件:注册回调函数 rm_get_arm_event_call_back:
①捕获设备到位事件(如运动完成、超时等);
②通过回调参数 device 判断触发事件的具体设备类型 | +| -5 | 单线程阻塞模式超时未接收到返回,请确保超时时间设置合理。| - 检查超时时长设置:单线程阻塞模式下,支持配置等待设备运动完成的超时时间,务必确保设置超时时间大于设备运动时间;
- 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。| +## ROS功能包机械臂相关指令使用说明 +该部分介绍如何来通过ROS话题查询和控制机械臂。 +### 关节配置 +#### 清除关节错误代码 + +| 功能描述 | 清除关节错误代码 | +| :---: | :---- | +| 参数说明 | Jointerrclear.msg
uint8 joint_num:对应关节序号,从基座到机械臂手爪端,六自由度序号依次为1~6,七自由度序号依次为1~7。 | +| 命令示例 | ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1 " | +| 返回值 | true-设置成功,false-设置失败 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_joint_err_clear_result | + +### 版本查询 +#### 查询机械臂基本信息 +| 功能描述 | 查询机械臂基本信息 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_robot_info_cmd std_msgs/msg/Empty "{}" | +| 返回值 | RobotInfo.msg
uint8 arm_dof:机械臂自由度(关节数量)
uint8 arm_model: 机械臂型号 示例:0=RM_65, 1=RM_75, 2=RML_63I(已弃用), 3=RML_63II,4=RML_63III,5=ECO_65,6=ECO_62,7=GEN_72,8=ECO63,9=通用机器人
uint8 force_type 末端力传感器版本,示例:0=标准版, 1=一维力版, 2=六维力版, 3=一体化六维力版
uint8 robot_controller_version机械臂控制器版本(3:三代,4:四代)
bool state:是否读取成功。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_robot_info_result | +#### 查询机械臂软件版本 +| 功能描述 | 查询机械臂软件版本 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_arm_software_version_cmd std_msgs/msg/Empty "{}" | +| 返回值 | Armsoftversion.msg
string product_version:机械臂型号
string controller_version:机械臂控制器版本,若为四代控制器,则该字段为"4.0"
string algorithm_info:算法库信息
Softwarebuildinfo ctrl_info:ctrl 层软件信息
string dynamic_info :动力学版本(三代)
Softwarebuildinfo plan_info:plan 层软件信息(三代)
Softwarebuildinfo com_info :communication 模块软件信息(四代)
Softwarebuildinfo program_info:流程图编程模块软件信息(四代)
bool state :查询状态 成功true 失败false | +| 返回查询示例 | ros2 topic echo /rm_driver/get_arm_software_version_result | +#### 查询关节软件版本 +| 功能描述 | 查询关节软件版本 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_joint_software_version_cmd std_msgs/msg/Empty "{}" | +| 返回值 | Jointversion.msg
string[7] joint_version:获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8(三代控制器)
bool state :获取状态 true获取成功 false获取失败。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_joint_software_version_result | +#### 查询末端接口板软件版本号 +| 功能描述 | 查询末端接口板软件版本号 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_tool_software_version_cmd std_msgs/msg/Empty "{}" | +| 返回值 | Toolsoftwareversionv4.msg
string tool_version: End interface board software version number
boolean state: Query status, success returns true, failure returns false | +| 返回查询示例 | ros2 topic echo /rm_driver/get_tool_software_version_result | + +### 工作坐标系设置 +#### 切换当前工作坐标系 +| 功能描述 | 切换当前工作坐标系 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::String | +| 命令示例 | ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'" | +| 返回值 | true-设置成功,false-设置失败 | +| 返回查询示例 | ros2 topic echo /rm_driver/change_work_frame_result | +### 坐标系查询 +#### 查询当前工具坐标系 +| 功能描述 | 查询当前工具坐标系 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 当前工具坐标系名称 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_current_tool_frame_result | +#### 查询所有工具坐标系名称 +| 功能描述 | 查询所有工具坐标系 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 当前工具坐标系所有名称 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_all_tool_frame_result | +#### 查询当前工作坐标系 +| 功能描述 | 查询当前工作坐标系 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" | +| 返回值 | true-设置成功,false-设置失败 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_curr_workFrame_result | +#### 查询所有工作坐标系 +| 功能描述 | 查询所有工作坐标系 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 所有工作坐标系名称 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_all_work_frame_result | +### 机械臂状态查询 +#### 获取机械臂当前状态-返回各关节角度和欧拉角 +| 功能描述 | 获取机械臂当前状态 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 当前机械臂关节状态(角度)+位姿信息(欧拉角)+报错信息 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_current_arm_original_state_result | +#### 获取机械臂当前状态-返回各关节弧度和四元数 +| 功能描述 | 获取机械臂当前状态 | +| :---: | :---- | +| 参数说明 | ROS自带msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 当前机械臂关节状态(弧度)+位姿信息(四元数)+报错信息 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_current_arm_state_result | +### 机械臂运动规划 +#### 关节空间运动 +| 功能描述 | 关节空间运动MOVEJ | +| :---: | :---- | +| 参数说明 | Movej.msg
float32[6] joint:关节角度,单位:弧度。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 | +| 命令示例 | 六自由度
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0]
speed: 20
block: true
dof: 6"
七自由度
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0, 0]
speed: 20
block: true
trajectory_connect: 0
dof: 7" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/movej_result | +#### 笛卡尔空间直线运动 +| 功能描述 | 笛卡尔空间直线运动MOVEL | +| :---: | :---- | +| 参数说明 | Movel.msg
geometry_msgs/Pose pose:机械臂位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 | +| 命令示例 | 先使用MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: -0.317239
y: 0.120903
z: 0.255765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
block: true"
后使用MoveL
ros2 topic pub --once /rm_driver/movel_cmd rm_ros_interfaces/msg/Movel "pose:
position:
x: -0.317239
y: 0.120903
z: 0.295765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
trajectory_connect: 0
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/movel_result | +#### 笛卡尔空间直线偏移运动 +| 功能描述 | 笛卡尔空间直线偏移运动 | +| :---: | :---- | +| 参数说明 | Moveloffset.msg
geometry_msgs/Pose pose:位置姿态偏移,位置单位:米,姿态单位:弧度
int32 speed:速度百分比系数,1~100
int32 r:交融半径百分比系数,0~100。
bool trajectory_connect:轨迹连接标志,0立即规划并执行轨迹,不与后续轨迹连接。1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。
bool frame_type:参考坐标系类型,0工作坐标,1工具坐标
bool block:阻塞设置。多线程模式下,0表示非阻塞模式,发送指令后立即返回;1表示阻塞模式,等待机械臂到达目标位置或规划失败后才返回。单线程模式下,0表示非阻塞模式,发送指令后立即返回;其他值时,阻塞模式并设置超时时间,根据运动时间设置,单位为秒。| +| 命令示例 | 先使用MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.255765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}},speed: 20, trajectory_connect: 0, block: true}"
后使用Movel_offset
ros2 topic pub --once /rm_driver/movel_offset_cmd rm_ros_interfaces/msg/Moveloffset "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.295765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}}, speed: 20 ,r: 0 ,trajectory_connect: false, frame_type: false,block: false}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/movel_offset_result | + +#### 笛卡尔空间圆弧运动 +| 功能描述 | 笛卡尔空间圆弧运动MOVEC | +| :---: | :---- | +| 参数说明 | Movec.msg
geometry_msgs/Pose pose_mid:中间位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
geometry_msgs/Pose pose_end:终点位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 | +| 命令示例 | 首先使用movej_p到达指定位置
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: 0.274946
y: -0.058786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 0
block: true"
使用movec到达指定位置
ros2 topic pub --once /rm_driver/movec_cmd rm_ros_interfaces/msg/Movec "pose_mid:
position:
x: 0.324946
y: -0.008786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
pose_end:
position:
x: 0.274946
y: 0.041214
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 20
trajectory_connect: 0
block: false
loop: 0" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/movec_result | +#### 关节角度CANFD透传 +| 功能描述 | 关节角度CANFD透传 | +| :---: | :---- | +| 参数说明 | Jointpos.msg
float32[6] joint:关节角度,单位:弧度。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
float32 expand:拓展关节,单位:弧度。 | +| 命令示例 | 透传需要连续发送多个连续的点实现,单纯靠以下命令并不能实现功能,当前moveit2控制使用了角度透传的控制方式。
ros2 topic pub /rm_driver/movej_canfd_cmd rm_ros_interfaces/msg/Jointpos "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
dof: 6" | +| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 | +#### 自定义高跟随模式关节角度CANFD透传 +| 功能描述 | 自定义高跟随模式关节角度CANFD透传 | +| :---: | :---- | +| 参数说明 | Jointposcustom.msg
float32[6] joint:关节角度,单位:弧度。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
float32 expand:拓展关节,单位:弧度。
uint8 trajectory_mode: 高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。
uint8 radio: 设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好 | +| 命令示例 | 透传需要连续发送多个连续的点实现,单纯靠以下命令并不能实现功能,当前moveit2控制使用了角度透传的控制方式。
ros2 topic pub /rm_driver/movej_canfd_custom_cmd rm_ros_interfaces/msg/Jointposcustom "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
trajectory_mode: 0
radio: 0
dof: 6" | +| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 | + +#### 位姿CANFD透传 +| 功能描述 | 位姿CANFD透传 | +| :---: | :---- | +| 参数说明 | Cartepos.msg
geometry_msgs/Pose pose:透传位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。 | +| 命令示例 | 需要是大量(10个以上)位置连续 的点,单纯靠以下命令并不能实现功能,以2ms以上的周期持续发布。
ros2 topic pub /rm_driver/movep_canfd_cmd rm_ros_interfaces/msg/Cartepos "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false" | +| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 | +#### 自定义高跟随模式位姿CANFD透传 +| 功能描述 | 自定义高跟随模式位姿CANFD透传 | +| :---: | :---- | +| 参数说明 | Carteposcustom.msg
geometry_msgs/Pose pose:透传位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
uint8 trajectory_mode: 高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。
uint8 radio: 设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好| +| 命令示例 | 需要是大量(10个以上)位置连续 的点,单纯靠以下命令并不能实现功能,以2ms以上的周期持续发布。
ros2 topic pub /rm_driver/movep_canfd_custom_cmd rm_ros_interfaces/msg/Carteposcustom
"pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false
trajectory_mode: 0
radio: 0" | +| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 | +#### 关节空间规划到目标位姿 +| 功能描述 | 关节空间规划到目标位姿MOVEJP | +| :---: | :---- | +| 参数说明 | Movejp.msg
geometry_msgs/Pose pose:目标位姿,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: -0.317239
y: 0.120903
z: 0.255765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/movej_p_result | +#### 轨迹急停 +| 功能描述 | 运动规划轨迹急停 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/move_stop_result | +#### 紧急停止 +| 功能描述 | 设置机械臂急停状态 | +| :---: | :---- | +| 参数说明 | rm_ros_interfaces/Stop 急停状态,true:急停,false:恢复| +| 命令示例 | ros2 topic pub --once /rm_driver/emergency_stop_cmd rm_ros_interfaces/Stop "state: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/emergency_stop_result | +### 示教指令 +#### 关节示教 +| 功能描述 | 关节示教 | +| :---: | :---- | +| 参数说明 | Jointteach.msg
uint8 num:示教关节的序号,1~7
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100 | +| 命令示例 | ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1
direction: 0
speed: 10" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_joint_teach_result | +#### 位置示教 +| 功能描述 | 位置示教 | +| :---: | :---- | +| 参数说明 | Posteach.msg
uint8 type:示教类型 输入0X轴方向、1Y轴方向、2Z轴方向
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100。| +| 命令示例 | ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2
direction: 0
speed: 10" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_pos_teach_result | +#### 姿态示教 +| 功能描述 | 姿态示教 | +| :---: | :---- | +| 参数说明 | Ortteach.msg
uint8 type:示教类型 输入0RX轴方向、1RY轴方向、2RZ轴方向
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100。| +| 命令示例 | ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2
direction: 0
speed: 10" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_ort_teach_result | +#### 示教停止 +| 功能描述 | 示教停止 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_stop_teach_result | +### 轨迹列表 +#### 查询轨迹列表 +| 功能描述 | 查询轨迹列表 | +| :---: | :---- | +| 参数说明 | Gettrajectorylist.msg
int32 page_num: 页码。
int32 page_size: 每页大小。
string vague_search: 模糊搜索。 | +| 命令示例 | ros2 topic pub --once /rm_driver/get_trajectory_file_list_cmd rm_ros_interfaces/msg/Gettrajectorylist "{page_num: 1,page_size: 10,vague_search: 's'}" | +| 返回值 | Trajectorylist.msg
int32 page_num # 页码
int32 page_size # 每页大小
int32 total_size # 列表长度
string vague_search # 模糊搜索
Trajectoryinfo[] tra_list # 返回符合的轨迹列表
bool state # 查询状态 成功true 失败false | +| 返回查询示例 | ros2 topic echo /rm_driver/get_trajectory_file_list_result | +#### 开始运行指定轨迹 +| 功能描述 | 开始运行指定轨迹 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::String | +| 命令示例 | ros2 topic pub --once /rm_driver/set_run_trajectory_cmd std_msgs/msg/String "data: 'sss'" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_run_trajectory_result | +#### 删除指定轨迹文件 +| 功能描述 | 删除指定轨迹文件 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::String | +| 命令示例 | ros2 topic pub --once /rm_driver/delete_trajectory_file_cmd std_msgs/msg/String "data: 'sss'" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/delete_trajectory_file_result | +#### 保存轨迹文件 +| 功能描述 | 保存轨迹文件 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::String | +| 命令示例 | ros2 topic pub --once /rm_driver/save_trajectory_file_cmd std_msgs/msg/String "data: 'test'" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/save_trajectory_file_result | +#### 查询流程图编程状态 +| 功能描述 | 查询流程图编程状态 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs/msg/Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_flowchart_program_run_state_cmd std_msgs/msg/Empty "{}" | +| 返回值 | Flowchartrunstate.msg
int run_state; #运行状态 0 未开始 1运行中 2暂停中
int id;#当前使能的文件id。
char name[32]; #当前使能的文件名称。
int plan_speed;#当前使能的文件全局规划速度比例 1-100。
int step_mode;#单步模式,0为空,1为正常, 2为单步。
char modal_id[50];#运行到的流程图块的id。
bool state:正常运行返回true,未正常运行则返回false | +| 返回查询示例 | ros2 topic echo /rm_driver/get_flowchart_program_run_state_result | +### Modbus模式查询与配置 +#### 配置控制器通讯端口RS485模式 +| 功能描述 | 配置控制器通讯端口RS485模式 | +| :---: | :---- | +| 参数说明 | RS485params.msg
int32 mode: 0-RS485串行通讯,1-modbus-RTU主站模式,2-modbus-RTU从站模式。
int32 baudrate: 当前支持9600 19200 38400 57600 115200 230400 460800。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_controller_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_controller_rs485_mode_result | +#### 查询控制器RS485模式 +| 功能描述 | 查询控制器RS485模式 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driv/get_controller_rs485_mode_cmd std_msgs/msg/Empty "{}" | +| 返回值 | RS485params.msg
int32 mode # 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。
int32 baudrate # 波特率(当前支持9600 19200 38400 57600 115200 230400 460800)
bool state # 查询状态 true查询成功 false查询失败 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_controller_rs485_mode_result | +#### 配置工具端RS485模式 +| 功能描述 | 配置工具端RS485模式 | +| :---: | :---- | +| 参数说明 | RS485params.msg
int32 mode: 0-设置工具端RS485端口为RTU主站,1-灵巧手模式,2-夹爪模式。
int32 baudrate: 当前支持9600,115200,460800。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_tool_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_tool_rs485_mode_result | +#### 查询工具端RS485模式 +| 功能描述 | 查询工具端RS485模式 | +| :---: | :---- | +| 参数说明 | ROS官方msg std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub --once /rm_driver/get_tool_rs485_mode_cmd std_msgs/msg/Empty "{}" | +| 返回值 | RS485params.msg
int32 mode # 0-设置工具端RS485端口为RTU主站,1-灵巧手模式,2-夹爪模式。
int32 baudrate # 波特率(当前支持9600 19200 38400 57600 115200 230400 460800)
bool state # 查询状态 true查询成功 false查询失败。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_tool_rs485_mode_result | +### ModbusTCP主站 +#### 新增ModbusTCP主站 +| 功能描述 | 新增ModbusTCP主站 | +| :---: | :---- | +| 参数说明 | Modbustcpmasterinfo.msg
string master_name: Modbus主站名称。
string ip: TCP主站IP地址。
int32 port: TCP主站端口号。 | +| 命令示例 | ros2 topic pub --once /rm_driver/add_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',ip: '127.0.0.1',port: 502}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/add_modbus_tcp_master_result | +#### 更新ModbusTCP主站 +| 功能描述 | 更新ModbusTCP主站 | +| :---: | :---- | +| 参数说明 | Modbustcpmasterinfo.msg
string master_name: Modbus原本的主站名称。
string new_master_name: Modbus新的主站名称。
string ip: TCP主站IP地址。
int32 port: TCP主站端口号。 | +| 命令示例 | ros2 topic pub /rm_driver/update_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',new_master_name: '125',ip: '127.0.0.1',port: 502}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/update_modbus_tcp_master_result | +#### 删除ModbusTCP主站 +| 功能描述 | 删除ModbusTCP主站 | +| :---: | :---- | +| 参数说明 | Mastername.msg
string master_name: Modbus主站名称。 | +| 命令示例 | ros2 topic pub --once /rm_driver/delete_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/delete_modbus_tcp_master_result | +#### 查询指定Modbus主站 +| 功能描述 | 查询指定Modbus主站 | +| :---: | :---- | +| 参数说明 | Mastername.msg
string master_name: Modbus主站名称。 | +| 命令示例 | ros2 topic pub --once /rm_driver/get_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" | +| 返回值 | Modbustcpmasterinfo.msg
string master_name # Modbus主站名称,最大长度15个字符,不超过15个字符
string ip # TCP主站IP地址
int32 port # TCP主站端口号
bool state # 查询状态信息,失败为false,成功为true
失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_modbus_tcp_master_result | +#### 查询Modbus主站列表 +| 功能描述 | 查询Modbus主站列表 | +| :---: | :---- | +| 参数说明 | Getmodbustcpmasterlist.msg
int32 page_num: 页码。
int32 page_size: 每页大小。
string vague_search: 模糊搜索,若输入为空则返回所有主站列表。 | +| 命令示例 | ros2 topic pub --once /rm_driver/get_modbus_tcp_master_list_cmd rm_ros_interfaces/msg/Getmodbustcpmasterlist "{page_num: 1,page_size: 10,vague_search: '1'}" | +| 返回值 | Modbustcpmasterlist.msg
uint8 page_num # 页码
uint8 page_size # 每页大小
uint8 total_size # 列表长度
string vague_search # 模糊搜索
Modbustcpmasterinfo[] master_list # 返回符合的TCP主站列表
bool state # 查询状态 成功true 失败false
失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_modbus_tcp_master_list_result | + +### 工具端控制器端ModbusRTU协议读写数据 +#### ModbusRTU协议读线圈 +| 功能描述 | ModbusRTU协议读线圈 | +| :---: | :---- | +| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。
int32 num: 要读的数据的数量,数据长度不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 1, type: 0, num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_coils_result | +#### ModbusRTU协议写线圈 +| 功能描述 | ModbusRTU协议写线圈 | +| :---: | :---- | +| 参数说明 | Modbusrtuwriteparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。
int32 num: 要写的数据的数量,最大不超过100。
int32[] data: 要写的数据,数据长度与num对应。 | +| 命令示例 | ros2 topic pub /rm_driver/write_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 1, type: 0, num: 2, data: [1,1]}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_rtu_coils_result | +#### ModbusRTU协议读离散量输入 +| 功能描述 | ModbusRTU协议读离散量输入 | +| :---: | :---- | +| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_input_status_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_input_status_result | +#### ModbusRTU协议读保持寄存器 +| 功能描述 | ModbusRTU协议读保持寄存器 | +| :---: | :---- | +| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_holding_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_holding_registers_result | +#### ModbusRTU协议写保持寄存器 +| 功能描述 | ModbusRTU协议写保持寄存器 | +| :---: | :---- | +| 参数说明 | Modbusrtuwriteparams.msg
int32 address: 数据起始地址
int32 device: 外设设备地址
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。
int32 num: 要写的数据的数量,最大不超过100
int32[] data: 要写的数据,数据长度与num对应。 | +| 命令示例 | ros2 topic pub /rm_driver/write_modbus_rtu_registers_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_rtu_registers_result | +#### ModbusRTU协议读输入寄存器 +| 功能描述 | ModbusRTU协议读输入寄存器 | +| :---: | :---- | +| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_input_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_input_registers_result | +### 控制器ModbusTCP协议读写数据 +#### ModbusTCP协议读线圈 +| 功能描述 | ModbusTCP协议读线圈 | +| :---: | :---- | +| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_coils_result | +#### ModbusTCP协议写线圈 +| 功能描述 | ModbusTCP协议写线圈 | +| :---: | :---- | +| 参数说明 | Modbustcpwriteparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 写入数据数量,最大不超过100。
int32[] data: 写入的数据,数据长度与num对应。 | +| 命令示例 | ros2 topic pub /rm_driver/write_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_tcp_coils_result | +#### ModbusTCP协议读离散量输入 +| 功能描述 | ModbusTCP协议读离散量输入 | +| :---: | :---- | +| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_input_status_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_input_status_result | +#### ModbusTCP协议读保持寄存器 +| 功能描述 | ModbusTCP协议读保持寄存器 | +| :---: | :---- | +| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_holding_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_holding_registers_result | +#### ModbusTCP协议写保持寄存器 +| 功能描述 | ModbusTCP协议写保持寄存器 | +| :---: | :---- | +| 参数说明 | Modbustcpwriteparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 写入数据数量,最大不超过100。
int32[] data: 写入的数据,数据长度与num对应。 | +| 命令示例 | ros2 topic pub /rm_driver/write_modbus_tcp_registers_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_tcp_registers_result | +#### ModbusTCP协议读输入寄存器 +| 功能描述 | ModbusTCP协议读输入寄存器 | +| :---: | :---- | +| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 | +| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_input_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" | +| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_input_registers_result | +### 末端工具IO配置 +#### 设置工具端电源输出 +| 功能描述 | 设置工具端电源输出 | +| :---: | :---- | +| 参数说明 | ROS自带消息文件:std_msgs::msg::UInt16
uint16 data:电源输出类型,范围:0~3 0-0V,1-5V,2-12V,3-24V | +| 命令示例 | ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_tool_voltage_result | +### 末端手爪控制 +睿尔曼机械臂末端配备了因时机器人公司的EG2-4C2手爪,为了便于用户操作手爪,机械臂控制器对用户适配了手爪的ROS控制方式 +#### 设置夹爪力控夹取 +| 功能描述 | 设置夹爪力控夹取 | +| :---: | :---- | +| 参数说明 | Gripperpick.msg
uint16 speed:1~1000,代表手爪开合速度,无量纲。
uint16 force:1~1000,代表手爪夹持力,最大1.5kg。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_pick_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_pick_result | +#### 设置夹爪持续力控夹取 +| 功能描述 | 设置夹爪持续力控夹取 | +| :---: | :---- | +| 参数说明 | Gripperpick.msg
uint16 speed:1~1000,代表手爪开合速度,无量纲。
uint16 force:1~1000,代表手爪夹持力,最大1.5kg。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_pick_on_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_pick_on_result | +#### 夹爪到达指定位置 +| 功能描述 | 夹爪到达指定位置 | +| :---: | :---- | +| 参数说明 | Gripperset.msg
uint16 position:手爪目标位置,范围:1~1000,代表手爪开口度:0~70mm
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500
block: true
timeout: 1000" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_position_result | +### 拖动示教及轨迹复现 +#### 设置力位混合控制 +| 功能描述 | 设置力位混合控制 | +| :---: | :---- | +| 参数说明 | Setforceposition.msg
uint8 sensor: 0-一维力;1-六维力
uint8 mode: 0-基坐标系力控;1-工具坐标系力控
uint8 direction: 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向
int16 n: 力的大小,单位N,精确到0.1N | +| 命令示例 | ros2 topic pub --once /rm_driver/set_force_postion_cmd rm_ros_interfaces/msg/Setforceposition "sensor: 1
mode: 0
direction: 2
n: 3" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_force_postion_result | +#### 结束力位混合控制 +| 功能描述 | 结束力位混合控制 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/stop_force_postion_result | + + +### 末端六维力传感器的使用 +睿尔曼RM-65F机械臂末端配备集成式六维力传感器,无需外部走线,用户可直接通过ROS话题对六维力进行操作。 +#### 查询六维力数据 +| 功能描述 | 查询六维力数据 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub rm_driver/get_force_data_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回对应坐标系六维力数据。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_force_data_result原始数据
ros2 topic echo /rm_driver/get_zero_force_data_result系统受力数据
ros2 topic echo /rm_driver/get_work_force_data_result工作坐标系受力数据
ros2 topic echo /rm_driver/get_tool_force_data_result工具坐标系受力数据 | +#### 清空六维力数据 +| 功能描述 | 清空六维力数据 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/clear_force_data_result | +### 末端五指灵巧手控制 +睿尔曼RM-65机械臂末端配备了五指灵巧手,可通过ROS对灵巧手进行设置。 +#### 设置灵巧手手势序号 +| 功能描述 | 设置灵巧手手势序号 | +| :---: | :---- | +| 参数说明 | Handposture.msg
uint16 posture_num:预先保存在灵巧手内的手势序号,范围:1~40。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。
uint16 timeout : timeout 阻塞模式下超时时间设置,单位:秒 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_posture_cmd rm_ros_interfaces/msg/Handposture "posture_num: 1
block: true
timeout: 1000" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_posture_result | +#### 设置灵巧手动作序列 +| 功能描述 | 设置灵巧手动作序列 | +| :---: | :---- | +| 参数说明 | Handseq.msg
uint16 seq_num:预先保存在灵巧手内的序列序号,范围:1~40。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。
uint16 timeout : timeout 阻塞模式下超时时间设置,单位:秒 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_seq_cmd rm_ros_interfaces/msg/Handseq "seq_num: 1
block: true
timeout: 1000" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_seq_result | +#### 设置灵巧手各自由度角度 +| 功能描述 | 设置灵巧手各自由度角度 | +| :---: | :---- | +| 参数说明 | Handangle.msg
int16[6] hand_angle:手指角度数组,范围:0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_angle_result | +#### 设置灵巧手速度 +| 功能描述 | 设置灵巧手速度 | +| :---: | :---- | +| 参数说明 | Handspeed.msg
uint16 hand_speed:手指速度,范围:1~1000。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_speed_cmd rm_ros_interfaces/msg/Handspeed "hand_speed: 200" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_speed_result | +#### 设置灵巧手力阈值 +| 功能描述 | 设置灵巧手力阈值 | +| :---: | :---- | +| 参数说明 | Handforce.msg
uint16 hand_force:手指力,范围:1~1000。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_force_cmd rm_ros_interfaces/msg/Handforce "hand_force: 200" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_force_result | +#### 设置灵巧手角度跟随 +| 功能描述 | 设置灵巧手角度跟随 | +| :---: | :---- | +| 参数说明 | Handangle.msg
int16[6] hand_angle:手指角度数组,范围(根据实际设备属性,以下为因时参考):0~2000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_follow_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_follow_angle_result | +#### 设置灵巧手姿态跟随 +| 功能描述 | 设置灵巧手姿态跟随 | +| :---: | :---- | +| 参数说明 | Handangle.msg
int16[6] hand_angle:手指姿态数组,范围(根据实际设备属性,以下为因时参考):0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_follow_pos_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_follow_pos_result | +### 升降机构 +睿尔曼机械臂可集成自主研发升降机构。 +#### 升降机构速度开环控制 +| 功能描述 | 升降机构速度开环控制 | +| :---: | :---- | +| 参数说明 | Liftspeed.msg
int16 speed:速度百分比,-100~100,Speed < 0:升降机构向下运动,Speed > 0:升降机构向上运动,Speed = 0:升降机构停止运动。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_lift_speed_result | +#### 升降机构位置闭环控制 +| 功能描述 | 升降机构位置闭环控制 | +| :---: | :---- | +| 参数说明 | Liftheight.msg
uint16 height:目标高度,单位 mm,范围:0-2600。
uint16 speed:速度百分比,1-100。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0
speed: 10
block: true" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo rm_driver/set_lift_height_result | +#### 获取升降机构状态 +| 功能描述 | 获取升降机构状态 | +| :---: | :---- | +| 参数说明 | Liftstate.msg
int16 height:当前高度。
int16 current:当前电流。
uint16 err_flag:驱动错误代码。 | +| 命令示例 | ros2 topic pub /rm_driver/get_lift_state_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:升降机构当前状态;失败返回:driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_lift_state_result | +### 末端生态协议 +末端生态协议支持下的末端设备基础信息与实时信息的读取。 +#### 设置末端生态协议模式 +| 功能描述 | 设置末端生态协议模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Int32
0-禁用协议;
9600-开启协议(波特率9600);
115200-开启协议(波特率115200);
256000-开启协议(波特率256000);
460800-开启协议(波特率460800)。| +| 命令示例 | ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_rm_plus_mode_result | +#### 查询末端生态协议模式 +| 功能描述 | 查询末端生态协议模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 0-禁用协议;
9600-开启协议(波特率9600);
115200-开启协议(波特率115200);
256000-开启协议(波特率256000);
460800-开启协议(波特率460800)。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_rm_plus_mode_result | +#### 设置触觉传感器模式 +| 功能描述 | 设置触觉传感器模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Int32
0-关闭触觉传感器;
1-打开触觉传感器(返回处理后数据);
2-打开触觉传感器(返回原始数据)。 | +| 命令示例 | ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0" | +| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_rm_plus_touch_result | +#### 获取触觉传感器模式 +| 功能描述 | 获取触觉传感器模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/get_rm_plus_touch_cmd std_msgs::msg::Empty "{}" | +| 返回值 | std_msgs::msg::Int32
0-关闭触觉传感器;
1-打开触觉传感器(返回处理后数据);
2-打开触觉传感器(返回原始数据)。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_rm_plus_touch_result | +### 透传力位混合控制补偿 +针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。 +在进行力的操作之前,如果未进行力数据标定,可使用清空一维力、六维力数据接口对零位进行标定。 +#### 开启透传力位混合控制补偿模式 +| 功能描述 | 开启透传力位混合控制补偿模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/start_force_position_move_result | +#### 关闭透传力位混合控制补偿模式 +| 功能描述 | 关闭透传力位混合控制补偿模式 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::Empty | +| 命令示例 | ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/stop_force_position_move_result | +#### 透传力位混合补偿-关节 +| 功能描述 | 透传力位混合补偿(关节) | +| :---: | :---- | +| 参数说明 | Forcepositionmovejoint.msg
float32[6] joint:目标关节弧度
uint8 sensor:所使用传感器类型,0-一维力,1-六维力
uint8 mode:模式,0-沿基坐标系,1-沿工具端坐标系
int16 dir:力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向
float32 force:力的大小 单位0.1N
bool follow:是否高跟随,true:高跟随,false:低跟随。
uint8 dof:机械臂自由度 | +| 命令示例 | 需要是大量(10个以上)位置连续的点,以2ms以上的周期持续发布。
ros2 topic pub /rm_driver/force_position_move_joint_cmd rm_ros_interfaces/msg/Forcepositionmovejoint " joint: [0, 0, 0, 0, 0, 0]
sensor: 0
mode: 0
dir: 0
force: 0.0
follow: false
dof: 6 | +| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。 | +#### 透传力位混合补偿-位姿 +| 功能描述 | 透传力位混合补偿(位姿) | +| :---: | :---- | +| 参数说明 | Forcepositionmovepose.msg
geometry_msgs/Pose pose:目标位姿,x、y、z坐标(float类型,单位:m)+四元数。
uint8 sensor:所使用传感器类型,0-一维力,1-六维力
uint8 mode:模式,0-沿基坐标系,1-沿工具端坐标系
int16 dir:力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向
float32 force:力的大小 单位0.1N
bool follow:是否高跟随,true:高跟随,false:低跟随。 | +| 命令示例 | 需要是大量(10个以上)位置连续 的点,以2ms以上的周期持续发布。
ros2 topic pub /rm_driver/force_position_move_pose_cmd rm_ros_interfaces/msg/Forcepositionmovepose "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
sensor: 0
mode: 0
dir: 0
force: 0
follow: false" | +| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。 +### 机械臂状态主动上报 +#### 设置UDP机械臂状态主动上报配置 +| 功能描述 | 设置UDP 机械臂状态主动上报配置 | +| :---: | :---- | +| 参数说明 | Setrealtimepush.msg
uint16 cycle:设置广播周期,为5ms的倍数(默认1即1*5=5ms,200Hz)。
uint16 port:设置广播的端口号(默认8089)。
uint16 force_coordinate:设置系统外受力数据的坐标系(仅带有力传感器的机械臂支持)。
string ip:设置自定义的上报目标IP 地址(默认192.168.1.10)
bool hand_enable:是否使能灵巧手状态上报,true使能,false不使能。
aloha_state_enable: 是否使能aloha主臂状态上报,true使能,false不使能。
arm_current_status_enable: 是否使能机械臂状态上报,true使能,false不使能。
expand_state_enable: 是否使能扩展关节相关数据上报,true使能,false不使能。
joint_speed_enable: 是否使能关节速度上报,true使能,false不使能。
lift_state_enable: 是否使能升降关节数据上报,true使能,false不使能。
plus_base_enable: 末端设备基础信息上报,true使能,false不使能。
plus_state_enable: 末端设备实时信息上报,true使能,false不使能。 | +| 命令示例 | ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1
port: 8089
force_coordinate: 0
ip: '192.168.1.10'
hand_enable: false
aloha_state_enable: false
arm_current_status_enable: false
expand_state_enable: false
joint_speed_enable: false
lift_state_enable: false
plus_base_enable: false
plus_state_enable: false" | +| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/set_realtime_push_result | +#### 查询UDP机械臂状态主动上报配置 +| 功能描述 | 查询UDP 机械臂状态主动上报配置 | +| :---: | :---- | +| 参数说明 | Setrealtimepush.msg
uint16 cycle:设置广播周期,为5ms的倍数(默认1即1*5=5ms,200Hz)。
uint16 port:设置广播的端口号(默认8089)。
uint16 force_coordinate:设置系统外受力数据的坐标系(仅带有力传感器的机械臂支持)。
string ip:设置自定义的上报目标IP 地址(默认192.168.1.10)
bool hand_enable:是否使能灵巧手状态上报,true使能,false不使能。
aloha_state_enable: 是否使能aloha主臂状态上报,true使能,false不使能。
arm_current_status_enable: 是否使能机械臂状态上报,true使能,false不使能。
expand_state_enable: 是否使能扩展关节相关数据上报,true使能,false不使能。
joint_speed_enable: 是否使能关节速度上报,true使能,false不使能。
lift_state_enable: 是否使能升降关节数据上报,true使能,false不使能。
plus_base_enable: 末端设备基础信息上报,true使能,false不使能。
plus_state_enable: 末端设备实时信息上报,true使能,false不使能。 | +| 命令示例 | ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}" | +| 返回值 | 成功设置信息;失败返回:driver终端返回错误码。 | +| 返回查询示例 | ros2 topic echo /rm_driver/get_realtime_push_result | +#### UDP机械臂状态主动上报 + +* 六维力 + +| 功能描述 | 六维力 | +| :---: | :---- | +| 参数说明 | Sixforce.msg
float32 force_fx:沿x轴方向受力大小。
float32 force_fy:沿y轴方向受力大小。
float32 force_fz:沿z轴方向受力大小。
float32 force_mx:沿x轴方向转动受力大小。
float32 force_my:沿y轴方向转动受力大小。
float32 force_mz:沿z轴方向转动受力大小。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_six_force | + +* 一维力 + +| 功能描述 | 一维力 | +| :---: | :---- | +| 参数说明 | Sixforce.msg
float32 force_fx:沿x轴方向受力大小。
float32 force_fy:沿y轴方向受力大小。
float32 force_fz:沿z轴方向受力大小。(仅该数值有效)
float32 force_mx:沿x轴方向转动受力大小。
float32 force_my:沿y轴方向转动受力大小。
float32 force_mz:沿z轴方向转动受力大小。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_one_force | + +* 机械臂错误 + +| 功能描述 | 机械臂错误 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::UInt16
uint16 data:机械臂报错信息。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_arm_err | + +* 系统错误 + +| 功能描述 | 系统错误 | +| :---: | :---- | +| 参数说明 | std_msgs::msg::UInt16
uint16 data:系统报错信息。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_sys_err | + +* 关节错误 + +| 功能描述 | 关节错误 | +| :---: | :---- | +| 参数说明 | Jointerrorcode.msg
uint16[] joint_error:每个关节报错信息。
Uint8 dof:机械臂自由度信息。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_error_code | + +* 机械臂弧度数据 + +| 功能描述 | 机械臂弧度数据 | +| :---: | :---- | +| 参数说明 | sensor_msgs::msg::JointState
builtin_interfaces/Time stamp
int32 sec:时间信息,秒。
uint32 nanosec:时间信息,纳秒。
string frame_id:坐标系名称。
string[] name:关节名称。
float64[] position:关节弧度信息。
float64[] velocity:关节速度信息。(暂未使用)
float64[] effort:关节受力信息。(暂未使用) | +| 查询示例 | ros2 topic echo /joint_states | + +* 位姿信息 + +| 功能描述 | 位姿信息 | +| :---: | :---- | +| 参数说明 | geometry_msgs::msg::Pose
Point position:机械臂当前坐标信息。
float64 x
float64 y
float64 z
Quaternion orientation:机械臂当前姿态信息。
float64 x 0
float64 y 0
float64 z 0
float64 w 1 | +| 查询示例 | ros2 topic echo /rm_driver/udp_arm_position | + +* 当前六维力传感器系统外受力数据 + +| 功能描述 | 当前六维力传感器系统外受力数据 | +| :---: | :---- | +| 参数说明 | Sixforce.msg
float32 force_fx:当前传感器沿x轴方向受外力大小。
float32 force_fy:当前传感器沿y轴方向受外力大小。
float32 force_fz:当前传感器沿z轴方向受外力大小。
float32 force_mx:当前传感器沿x轴方向转动受外力大小。
float32 force_my:当前传感器沿y轴方向转动受外力大小。
float32 force_mz:当前传感器沿z轴方向转动受外力大小。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_six_zero_force | + +* 当前一维力传感器系统外受力数据 + +| 功能描述 | 当前一维力传感器系统外受力数据 | +| :---: | :---- | +| 参数说明 | Sixforce.msg
float32 force_fx:当前传感器沿x轴方向受外力大小。
float32 force_fy:当前传感器沿y轴方向受外力大小。
float32 force_fz:当前传感器沿z轴方向受外力大小。(仅该数据有效)
float32 force_mx:当前传感器沿x轴方向转动受外力大小。
float32 force_my:当前传感器沿y轴方向转动受外力大小。
float32 force_mz:当前传感器沿z轴方向转动受外力大小。 | +| 查询示例 | ros2 topic echo /rm_driver/udp_one_zero_force | + +* 系统外受力数据参考坐标系 + +| 功能描述 | 系统外受力数据参考坐标系 | +| :----: | :---- | +| 参数说明 | std_msgs::msg::UInt16
uint16 data:系统外受力数据的坐标系,0 为传感器坐标系 1 为当前工作坐标系 2 为当前工具坐标系。该数据会影响一维力和六维力传感器系统外受力数据的参考坐标系 | +| 查询示例 | ros2 topic echo /rm_driver/udp_arm_coordinate | + +* 灵巧手力当前状态 + +| 功能描述 | 获取灵巧手力当前状态 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Handstatus.msg
uint16[6] hand_angle:#手指角度数组,范围:0~2000.
uint16[6] hand_pos:#手指位置数组,范围:0~1000.
uint16[6] hand_state:#手指状态,0正在松开,1正在抓取,2位置到位停止,3力到位停止,5电流保护停止,6电缸堵转停止,7电缸故障停止.
uint16[6] hand_force:#灵巧手自由度电流,单位mN.
uint16 hand_err:#灵巧手系统错误,1表示有错误,0表示无错误. | +| 查询示例 | ros2 topic echo /rm_driver/udp_hand_status | +* 机械臂当前状态 + +| 功能描述 | 获取机械臂当前状态 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Armcurrentstatus.msg
uint16 arm_current_status:机械臂状态
0 - RM_IDLE_E // 使能但空闲状态
1 - RM_MOVE_L_E // move L运动中状态
2 - RM_MOVE_J_E // move J运动中状态
3 - RM_MOVE_C_E // move C运动中状态
4 - RM_MOVE_S_E // move S运动中状态
5 - RM_MOVE_THROUGH_JOINT_E // 角度透传状态
6 - RM_MOVE_THROUGH_POSE_E // 位姿透传状态
7 - RM_MOVE_THROUGH_FORCE_POSE_E // 力控透传状态
8 - RM_MOVE_THROUGH_CURRENT_E // 电流环透传状态
9 - RM_STOP_E // 急停状态
10 - RM_SLOW_STOP_E // 缓停状态
11 - RM_PAUSE_E // 暂停状态
12 - RM_CURRENT_DRAG_E // 电流环拖动状态
13 - RM_SENSOR_DRAG_E // 六维力拖动状态
14 - RM_TECH_DEMONSTRATION_E // 示教状态 | +| 查询示例 | ros2 topic echo /rm_driver/udp_arm_current_status | + +* 当前关节电流 + +| 功能描述 | 当前关节电流 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointcurrent.msg
float32[] joint_current: 当前关节电流,精度 0.001mA | +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_current | + +* 当前关节使能状态 + +| 功能描述 | 当前关节使能状态 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointenflag.msg
bool[] joint_en_flag: 当前关节使能状态 ,1 为上使能,0 为掉使能| +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_en_flag | + +* 机械臂欧拉角位姿 + +| 功能描述 | 机械臂欧拉角位姿 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointposeeuler.msg
float32[3] euler: 当前路点姿态欧拉角,精度 0.001rad
float32[3] position:当前路点位置,精度 0.000001M| +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_pose_euler | + +* 当前关节速度 + +| 功能描述 | 当前关节速度 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointspeed.msg
float32[] joint_speed: 当前关节速度,精度0.02RPM。| +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_speed | + +* 当前关节温度 + +| 功能描述 | 当前关节温度 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointtemperature.msg
float32[] joint_temperature: 当前关节温度,精度 0.001℃| +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_temperature | +* 当前关节电压 + +| 功能描述 | 当前关节电压 | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Jointvoltage.msg
float32[] joint_voltage: 当前关节电压,精度 0.001V| +| 查询示例 | ros2 topic echo /rm_driver/udp_joint_voltage | +* 末端设备基础信息 + +| 功能描述 | 末端设备基础信息(末端生态协议支持) | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Rmplusbase.msg
string manu:# 设备厂家.
int8 type:设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪
string hv:硬件版本
string sv:软件版本
string bv:boot版本
int32 id:设备ID
int8 dof:自由度
int8 check:自检开关
int8 bee:蜂鸣器开关
bool force:力控支持
bool touch:触觉支持
int8 touch_num:触觉个数
int8 touch_sw:触觉开关
int8 hand:手方向 1 :左手 2: 右手
int32[12] pos_up:位置上限,单位:无量纲
int32[12] pos_low:位置下限,单位:无量纲
int32[12] angle_up:角度上限,单位:0.01度
int32[12] angle_low:角度下限,单位:0.01度
int32[12] speed_up:速度上限,单位:无量纲
int32[12] speed_low:速度下限,单位:无量纲
int32[12] force_up:力上限,单位:0.001N
int32[12] force_low:力下限,单位:0.001N| +| 查询示例 | ros2 topic echo /rm_driver/udp_rm_plus_base | +* 末端设备实时信息 + +| 功能描述 | 末端设备实时信息(末端生态协议支持) | +| :----: | :---- | +| 参数说明 | rm_ros_interfaces::msg::Rmplusstate.msg
int32 sys_state:系统状态.
int32[12] dof_state:各自由度当前状态
int32[12] dof_err:各自由度错误信息
int32[12] pos:各自由度当前位置
int32[12] speed:各自由度当前速度
int32[12] angle:各自由度当前角度,单位:0.01度
int32[12] current:各自由度当前电流,单位:mA
int32[18] normal_force:自由度触觉三维力的法向力
int32[18] tangential_force:自由度触觉三维力的切向力
int32[18] tangential_force_dir:自由度触觉三维力的切向力方向
uint32[12] tsa:自由度触觉自接近
uint32[12] tma:自由度触觉互接近
int32[18] touch_data:触觉传感器原始数据
int32[12] force:自由度力矩,单位0.001N| +| 查询示例 | ros2 topic echo /rm_driver/udp_rm_plus_state | diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h new file mode 100755 index 0000000..40ec038 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h @@ -0,0 +1,1032 @@ +#ifndef RM_DEFINE_H +#define RM_DEFINE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include + +#define ARM_DOF 7 +#define M_PI 3.14159265358979323846 + +#define RM_MOVE_NBLOCK 0 ///<机械臂运动设置,非阻塞模式 +#define RM_MOVE_MULTI_BLOCK 1 ///<机械臂运动设置,多线程阻塞模式 +static inline int RM_MOVE_SINGLE_BLOCK(int timeout){return timeout;} ///<机械臂运动设置,单线程阻塞模式超时时间 + +/** + * @brief 线程模式 + * @ingroup Init_Class + */ +typedef enum { + RM_SINGLE_MODE_E, ///< 单线程模式,单线程非阻塞等待数据返回 + RM_DUAL_MODE_E, ///< 双线程模式,增加接收线程监测队列中的数据 + RM_TRIPLE_MODE_E, ///< 三线程模式,在双线程模式基础上增加线程监测UDP接口数据 +}rm_thread_mode_e; + +/** + * @brief 机械臂型号 + * @ingroup Algo + */ +typedef enum{ + RM_MODEL_RM_65_E, ///< RM_65 + RM_MODEL_RM_75_E, ///< RM_75 + RM_MODEL_RM_63_I_E, ///< RML_63I(已弃用) + RM_MODEL_RM_63_II_E, ///< RML_63II + RM_MODEL_RM_63_III_E, ///< RML_63III + RM_MODEL_ECO_65_E, ///< ECO_65 + RM_MODEL_ECO_62_E, ///< ECO_62 + RM_MODEL_GEN_72_E, ///< GEN_72 + RM_MODEL_ECO_63_E, ///< ECO63 + RM_MODEL_UNIVERSAL_E +}rm_robot_arm_model_e; + +/** + * @brief 机械臂末端力传感器版本 + * @ingroup Algo + */ +typedef enum{ + RM_MODEL_RM_B_E, ///< 标准版 + RM_MODEL_RM_ZF_E, ///< 一维力版 + RM_MODEL_RM_SF_E, ///< 六维力版 + RM_MODEL_RM_ISF_E, ///< 一体化六维力版 +}rm_force_type_e; + +/** + * @brief 事件类型 + * @ingroup Init_Class + */ +typedef enum +{ + RM_NONE_EVENT_E, ///< 无事件 + RM_CURRENT_TRAJECTORY_STATE_E, ///< 当前轨迹到位 + RM_PROGRAM_RUN_FINISH_E, ///< 在线编程运行结束 +} rm_event_type_e; + +/** + * @brief 事件信息 + * @ingroup Init_Class + */ +typedef struct +{ + int handle_id; ///< 返回消息的机械臂id + rm_event_type_e event_type; ///< 事件类型,包含无事件、当前轨迹到位、在线编程运行结束 + bool trajectory_state; ///< 当前轨迹到位状态 + int device; ///< 到位设备,0:关节 1:夹爪 2:灵巧手 3:升降机构 4:扩展关节 其他:保留 + int trajectory_connect; ///< 是否连接下一条轨迹,0:全部到位,1:连接下一条轨迹 + int program_id; ///< 运行结束的在线编程程序id +}rm_event_push_data_t; + +/** + * @brief 机械臂当前规划类型 + * + */ +typedef enum +{ + RM_NO_PLANNING_E, ///< 无规划 + RM_JOINT_SPACE_PLANNING_E, ///< 关节空间规划 + RM_CARTESIAN_LINEAR_PLANNING_E, ///< 笛卡尔空间直线规划 + RM_CARTESIAN_ARC_PLANNING_E, ///< 笛卡尔空间圆弧规划 + RM_SPLINE_CURVE_MOTION_PLANNING_E, ///< 样条曲线运动规划 + RM_TRAJECTORY_REPLAY_PLANNING_E, ///< 示教轨迹复现规划 +}rm_arm_current_trajectory_e; + +typedef struct +{ + int joint_speed; ///< 关节速度。 + int lift_state; ///< 升降关节信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int expand_state; ///< 扩展关节信息(升降关节和扩展关节为二选一,优先显示升降关节)1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int hand_state; ///< 灵巧手状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态(1.7.0版本无这个) + int arm_current_status; ///< 机械臂当前状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int aloha_state; ///< aloha主臂状态是否上报。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int plus_base; ///< 末端设备基础信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int plus_state; ///< 末端设备实时信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 +}rm_udp_custom_config_t; + +/** + * @brief 机械臂主动上报接口配置 + * @ingroup UdpConfig + */ +typedef struct { + int cycle; ///< 广播周期,5ms的倍数 + bool enable; ///< 使能,是否主动上报 + int port; ///< 广播的端口号 + int force_coordinate; ///< 系统外受力数据的坐标系,-1不支持力传感器 0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 + char ip[28]; ///< 自定义的上报目标IP地址 + rm_udp_custom_config_t custom_config; ///< 自定义项内容 +} rm_realtime_push_config_t; + +/** + * @brief 四元数 + * + */ +typedef struct +{ + float w; + float x; + float y; + float z; +} rm_quat_t; + +/** + * @brief 位置坐标 + * + */ +typedef struct +{ + float x; //* unit: m + float y; + float z; +} rm_position_t; + +/** + * @brief 欧拉角 + * + */ +typedef struct +{ + float rx; //* unit: rad + float ry; + float rz; +} rm_euler_t; + +/** + * @brief 机械臂位置姿态结构体 + * @ingroup Algo + */ +typedef struct +{ + rm_position_t position; ///< 位置,单位:m + rm_quat_t quaternion; ///< 四元数 + rm_euler_t euler; ///< 欧拉角,单位:rad +}rm_pose_t; + +/** + * @brief 坐标系名称 + * 不超过10个字符 + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct +{ + char name[12]; +}rm_frame_name_t; + + +/** + * @brief 坐标系 + * @ingroup Algo + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct +{ + char frame_name[12]; ///< 坐标系名称 + rm_pose_t pose; ///< 坐标系位姿 + float payload; ///< 坐标系末端负载重量,单位:kg + float x; ///< 坐标系末端负载质心位置,单位:m + float y; ///< 坐标系末端负载质心位置,单位:m + float z; ///< 坐标系末端负载质心位置,单位:m +}rm_frame_t; + +typedef struct{ + char build_time[20]; ///< 编译时间 + char version[20]; ///< 版本号 +}rm_ctrl_version_t; + +typedef struct{ + char model_version[5]; ///< 动力学模型版本号 +}rm_dynamic_version_t; + +typedef struct{ + char build_time[20]; ///<编译时间 + char version[20]; ///< 版本号 +}rm_planinfo_t; + +typedef struct { + char version[20]; ///< 算法库版本号 +}rm_algorithm_version_t; + +typedef struct { + char build_time[20]; ///<编译时间 + char version[20]; ///< 版本号 +}rm_software_build_info_t; +/** + * @brief 机械臂软件信息 + * + */ +typedef struct +{ + char product_version[20]; ///< 机械臂型号 + char robot_controller_version[10]; ///< 机械臂控制器版本,若为四代控制器,则该字段为"4.0" + rm_algorithm_version_t algorithm_info; ///< 算法库信息 + rm_software_build_info_t ctrl_info; ///< ctrl 层软件信息 + rm_dynamic_version_t dynamic_info; ///< 动力学版本(三代) + rm_software_build_info_t plan_info; ///< plan 层软件信息(三代) + rm_software_build_info_t com_info; ///< communication 模块软件信息(四代) + rm_software_build_info_t program_info; ///< 流程图编程模块软件信息(四代) +}rm_arm_software_version_t; + +/** + * @brief 错误代码结构体 + * +*/ +typedef struct +{ + uint8_t err_len; ///< 错误代码个数 + int err[24]; ///< 错误代码数组 +}rm_err_t; + +/** + * @brief 机械臂当前状态 + * +*/ +typedef struct +{ + rm_pose_t pose; ///< 机械臂当前位姿 + float joint[ARM_DOF]; ///< 机械臂当前关节角度 + rm_err_t err; +}rm_current_arm_state_t; + +/** + * @brief 机械臂关节状态参数 + * +*/ +typedef struct +{ + float joint_current[ARM_DOF]; ///< 关节电流,单位mA,精度:0.001mA + bool joint_en_flag[ARM_DOF]; ///< 当前关节使能状态 ,1为上使能,0为掉使能 + uint16_t joint_err_code[ARM_DOF]; ///< 当前关节错误码 + float joint_position[ARM_DOF]; ///< 关节角度,单位°,精度:0.001° + float joint_temperature[ARM_DOF]; ///< 当前关节温度,精度0.001℃ + float joint_voltage[ARM_DOF]; ///< 当前关节电压,精度0.001V + float joint_speed[ARM_DOF]; ///< 当前关节速度,精度0.01RPM。 +}rm_joint_status_t; + +/** + * @brief 位置示教方向 + * + */ +typedef enum +{ + RM_X_DIR_E, ///< 位置示教,x轴方向 + RM_Y_DIR_E, ///< 位置示教,y轴方向 + RM_Z_DIR_E, ///< 位置示教,z轴方向 +}rm_pos_teach_type_e; + +/** + * @brief 姿态示教方向 + * + */ +typedef enum +{ + RM_RX_ROTATE_E, ///< 姿态示教,绕x轴旋转 + RM_RY_ROTATE_E, ///< 姿态示教,绕y轴旋转 + RM_RZ_ROTATE_E, ///< 姿态示教,绕z轴旋转 +}rm_ort_teach_type_e; + +/** + * @brief 数字IO配置结构体 + * io_mode:模式,0-通用输入模式、1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式 + * 7-输入进入力只动位置拖动模式(六维力版本可配置)、8-输入进入力只动姿态拖动模式(六维力版本可配置) + * 9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、10-输入外部轴最大软限位复用模式(外部轴模式可配置) + * 11-输入外部轴最小软限位复用模式(外部轴模式可配置)、12-输入初始位姿功能复用模式 + * 13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * io_state:数字io状态(0低 1高)(该成员在set时无效) + * io_real_time_config_t:实时调速功能,io配置 + * speed:速度取值范围0-100 (当io_mode不为14时,默认值为-1) + * mode :模式取值范围1或2 (当io_mode不为14时,默认值为-1) + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + */ +typedef struct +{ + int io_mode; // io_mode:模式0~14 + struct + { + int speed; // speed:速度取值范围0-100 + int mode; // mode :模式取值范围1或2 + }io_real_time_config_t; +}rm_io_config_t; + +/** + * @brief 数字IO状态获取结构体 + * io_state:数字io状态(0低 1高)(该成员在set时无效) + * io_config:io配置结构体 + */ +typedef struct +{ + int io_state; // io_state:数字io状态(0低 1高) + rm_io_config_t io_config; // io_config:数字io配置结构体 +}rm_io_get_t; + +/** + * @brief 复合模式拖动示教参数 + * + */ +typedef struct{ + int free_axes[6]; ///< 自由驱动方向[x,y,z,rx,ry,rz],0-在参考坐标系对应方向轴上不可拖动,1-在参考坐标系对应方向轴上可拖动 + int frame; ///< 参考坐标系,0-工作坐标系 1-工具坐标系。 + int singular_wall; ///< 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙,若无配置参数,默认启动拖动奇异墙 +}rm_multi_drag_teach_t; + +/** + * @brief 力位混合控制传感器枚举 + * + */ +typedef enum{ + RM_FP_OF_SENSOR_E = 0, ///<一维力 + RM_FP_SF_SENSOR_E, ///<六维力 +}rm_force_position_sensor_e; + +/** + * @brief 力位混合控制模式枚举 + * + */ +typedef enum{ + RM_FP_BASE_COORDINATE_E = 0, ///<基坐标系力控 + RM_FP_TOOL_COORDINATE_E, ///<工具坐标系力控 +}rm_force_position_mode_e; + +/** + * @brief 力位混合控制模式(单方向)力控方向枚举 + * + */ +typedef enum{ + RM_FP_X_E = 0, ///<沿X轴 + RM_FP_Y_E, ///<沿Y轴 + RM_FP_Z_E, ///<沿Z轴 + RM_FP_RX_E, ///<沿RX姿态方向 + RM_FP_RY_E, ///<沿RY姿态方向 + RM_FP_RZ_E, ///<沿RZ姿态方向 +}rm_force_position_dir_e; + +/** + * @brief 力位混合控制参数 + * + */ +typedef struct +{ + int sensor; ///< 传感器,0-一维力;1-六维力 + int mode; ///< 0-基坐标系力控;1-工具坐标系力控; + int control_mode[6]; ///< 6个力控方向(Fx Fy Fz Mx My Mz)的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模 4-力跟踪模式 8-力跟踪+姿态自适应模式 + float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。 + float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。 +}rm_force_position_t; + +/** + * @brief 透传力位混合补偿参数 + * 建议初始化方式,避免一些未知错误 + * rm_force_position_move_t my_fp_move = (rm_force_position_move_t){ 0 }; + */ +typedef struct +{ + int flag; ///< 0-下发目标角度,1-下发目标位姿 + rm_pose_t pose; ///< 当前坐标系下的目标位姿,支持四元数/欧拉角表示姿态。位置精度:0.001mm,欧拉角表示姿态,姿态精度:0.001rad,四元数方式表示姿态,姿态精度:0.000001 + float joint[ARM_DOF]; ///< 目标关节角度,单位:°,精度:0.001° + int sensor; ///< 传感器,0-一维力;1-六维力 + int mode; ///< 0-基坐标系力控;1-工具坐标系力控; + bool follow; ///< 表示驱动器的运动跟随效果,true 为高跟随,false 为低跟随。 + int control_mode[6]; ///< 6个力控方向的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模式 4-力跟踪模式 5-浮动+运动模式 6-弹簧+运动模式 7-力跟踪+运动模式 8-姿态自适应模式 + float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。 + float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。 + int trajectory_mode; ///< 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; ///< 曲线拟合模式0-100和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_force_position_move_t; + +/** + * @brief 角度透传模式结构体 + * 建议初始化方式,避免一些未知错误 + * rm_movej_canfd_mode_t my_j_canfd = (rm_movej_canfd_mode_t){ 0 }; + */ +typedef struct +{ + float* joint; // 关节角度(若为六轴机械臂,那么最后一个元素无效),单位° + float expand; // 扩展关节角度(若没有扩展关节,那么此成员值无效) + bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_movej_canfd_mode_t; + +/** + * @brief 姿态透传模式结构体 + * 建议初始化方式,避免一些未知错误 + * rm_movep_canfd_mode_t my_p_canfd = (rm_movep_canfd_mode_t){ 0 }; + */ +typedef struct +{ + rm_pose_t pose; // 位姿 (优先采用四元数表达) + bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_movep_canfd_mode_t; + +/** + * @brief 无线网络信息结构体 + * + */ +typedef struct{ + int channel; ///< 如果是 AP 模式,则存在此字段,标识 wifi 热点的物理信道号 + char ip[16]; ///< IP 地址 + char mac[18]; ///< MAC 地址 + char mask[16]; ///< 子网掩码 + char mode[5]; ///< ap 代表热点模式,sta 代表联网模式,off 代表未开启无线模式 + char password[16]; ///< 密码 + char ssid[32]; ///< 网络名称 (SSID) +}rm_wifi_net_t; + +/** + * @brief 机械臂所有状态参数 + * +*/ +typedef struct +{ + float joint_current[ARM_DOF]; ///< 关节电流,单位mA + int joint_en_flag[ARM_DOF]; ///< 关节使能状态 + float joint_temperature[ARM_DOF]; ///< 关节温度,单位℃ + float joint_voltage[ARM_DOF]; ///< 关节电压,单位V + int joint_err_code[ARM_DOF]; ///< 关节错误码 + rm_err_t err; ///< 错误代码 +}rm_arm_all_state_t; + +/** + * @brief 夹爪状态 + * + */ +typedef struct +{ + int enable_state; ///< 夹爪使能标志,0 表示未使能,1 表示使能 + int status; ///< 夹爪在线状态,0 表示离线, 1表示在线 + int error; ///< 夹爪错误信息,低8位表示夹爪内部的错误信息bit5-7 保留bit4 内部通bit3 驱动器bit2 过流 bit1 过温bit0 堵转 + int mode; ///< 当前工作状态:1 夹爪张开到最大且空闲,2 夹爪闭合到最小且空闲,3 夹爪停止且空闲,4 夹爪正在闭合,5 夹爪正在张开,6 夹爪闭合过程中遇到力控停止 + int current_force; ///< 夹爪当前的压力,单位g + int temperature; ///< 当前温度,单位℃ + int actpos; ///< 夹爪开口度 +}rm_gripper_state_t; + +/** + * @brief 六维力传感器数据结构体 + * +*/ +typedef struct { + float force_data[6]; ///< 当前力传感器原始数据,力的单位为N;力矩单位为Nm。 + float zero_force_data[6]; ///< 当前力传感器系统外受力数据,力的单位为N;力矩单位为Nm。 + float work_zero_force_data[6]; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 + float tool_zero_force_data[6]; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 +} rm_force_data_t; + +/** + * @brief 一维力传感器数据结构体 + * +*/ +typedef struct { + float Fz; ///< 原始数据 + float zero_Fz; ///< 传感器坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + float work_zero_Fz; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 + float tool_zero_Fz; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 +} rm_fz_data_t; + +/** + * @brief 外设数据读写参数结构体 + * +*/ +typedef struct { + int port; ///< 通讯端口,0-控制器RS485端口,1-末端接口板RS485接口,3-控制器ModbusTCP设备 + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int num; ///< 要读的数据的数量 +} rm_peripheral_read_write_params_t; + +/** + * @brief 升降机构、扩展关节状态结构体 + * +*/ +typedef struct { + int pos; ///< 扩展关节角度,单位度,精度 0.001°(若为升降机构高度,则单位:mm,精度:1mm,范围:0 ~2300) + int current; ///< 驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int mode; ///< 当前状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 +} rm_expand_state_t; + +/** + * @brief 文件下发 + * @ingroup OnlineProgramming + */ +typedef struct { + char project_path[300]; ///< 下发文件路径文件名 + int project_path_len; ///< 名称长度 + int plan_speed; ///< 规划速度比例系数 + int only_save; ///< 0-保存并运行文件,1-仅保存文件,不运行 + int save_id; ///< 保存到控制器中的编号 + int step_flag; ///< 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式 + int auto_start; ///< 设置默认在线编程文件,1-设置默认 0-设置非默认 + int project_type; ///< 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件 + // int err_line; ///< 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对 +} rm_send_project_t; + +/** + * @brief 在线编程存储信息 + * @ingroup OnlineProgramming + */ +typedef struct { + int id; ///< 在线编程文件id + int size; ///< 文件大小 + int speed; ///< 默认运行速度 + char trajectory_name[32]; ///< 文件名称 +}rm_trajectory_data_t; +/** + * @brief 查询在线编程列表 + * @ingroup OnlineProgramming + */ +typedef struct +{ + int page_num; // 页码 + int page_size; // 每页大小 + int list_size; //返回总数量 + char vague_search[32]; // 模糊搜索 + rm_trajectory_data_t trajectory_list[100]; // 符合的在线编程列表 +}rm_program_trajectorys_t; + +/** + * @brief 在线编程运行状态 + * @ingroup OnlineProgramming + */ +typedef struct +{ + int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中 + int id; ///< 运行轨迹编号 + int edit_id; ///< 上次编辑的在线编程编号 id + int plan_num; ///< 运行行数 + int total_loop; ///< 循环指令数量 + int step_mode; ///< 单步模式,1 为单步模式,0 为非单步模式 + int plan_speed; ///< 全局规划速度比例 1-100 + int loop_num[100]; ///< 循环行数 + int loop_cont[100]; ///< 对应循环次数 +}rm_program_run_state_t; + +/** + * @brief 流程图程序运行状态 + */ +typedef struct +{ + int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中 + int id; ///< 当前使能的文件id。 + char name[32]; ///< 当前使能的文件名称。 + int plan_speed; ///< 当前使能的文件全局规划速度比例 1-100。 + int step_mode; ///< 单步模式,0为空,1为正常, 2为单步。 + char modal_id[50]; ///< 运行到的流程图块的id。未运行则不返回 +}rm_flowchart_run_state_t; + +/** + * @brief 全局路点存储信息 + * @ingroup OnlineProgramming + */ +typedef struct +{ + char point_name[20]; ///< 路点名称 + float joint[ARM_DOF]; ///< 关节角度 + rm_pose_t pose; ///< 位姿信息 + char work_frame[12]; ///< 工作坐标系名称 + char tool_frame[12]; ///< 工具坐标系名称 + char time[50]; ///< 路点新增或修改时间 +}rm_waypoint_t; +/** + * @brief 全局路点列表 + * @ingroup OnlineProgramming + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的全局路点列表长度 + rm_waypoint_t points_list[100]; ///< 返回符合的全局路点列表 +}rm_waypoint_list_t; + +/** + * @brief 几何模型长方体参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x_min_limit; ///< 长方体基于世界坐标系 X 方向最小位置,单位 m + float x_max_limit; ///< 长方体基于世界坐标系 X 方向最大位置,单位 m + float y_min_limit; ///< 长方体基于世界坐标系 Y 方向最小位置,单位 m + float y_max_limit; ///< 长方体基于世界坐标系 Y 方向最大位置,单位 m + float z_min_limit; ///< 长方体基于世界坐标系 Z 方向最小位置,单位 m + float z_max_limit; ///< 长方体基于世界坐标系 Z 方向最大位置,单位 m +}rm_fence_config_cube_t; +/** + * @brief 几何模型点面矢量平面参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x1, y1, z1; ///< 点面矢量平面三点法中的第一个点坐标,单位 m + float x2, y2, z2; ///< 点面矢量平面三点法中的第二个点坐标,单位 m + float x3, y3, z3; ///< 点面矢量平面三点法中的第三个点坐标,单位 m +}rm_fence_config_plane_t; +/** + * @brief 几何模型球体参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x; ///< 表示球心在世界坐标系 X 轴的坐标,单位 m + float y; ///< 表示球心在世界坐标系 Y 轴的坐标,单位 m + float z; ///< 表示球心在世界坐标系 Z 轴的坐标,单位 m + float radius; ///< 表示半径,单位 m +}rm_fence_config_sphere_t; +/** + * @brief 几何模型参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + int form; ///< 形状,1 表示长方体,2 表示点面矢量平面,3 表示球体 + char name[12]; ///< 电子围栏名称,不超过 10 个字节,支持字母、数字、下划线 + rm_fence_config_cube_t cube; ///< 长方体参数 + rm_fence_config_plane_t plan; ///< 点面矢量平面参数 + rm_fence_config_sphere_t sphere; ///< 球体参数 +}rm_fence_config_t; + +/** + * @brief 几何模型名称结构体 + * @ingroup Electronic_Fence + */ +typedef struct +{ + char name[12]; ///< 几何模型名称,不超过10个字符 +}rm_fence_names_t; + +/** + * @brief 几何模型参数列表 + * @ingroup Electronic_Fence + */ +typedef struct +{ + rm_fence_config_t config[10]; +}rm_fence_config_list_t; +/** + * @brief 包络球参数 + * + */ +typedef struct{ + char name[12]; ///< 工具包络球体的名称,1-10 个字节,支持字母数字下划线 + float radius; ///< 工具包络球体的半径,单位 m + float x; ///< 工具包络球体球心基于末端法兰坐标系的 X 轴坐标,单位 m + float y; ///< 工具包络球体球心基于末端法兰坐标系的 Y 轴坐标,单位 m + float z; ///< 工具包络球体球心基于末端法兰坐标系的 Z 轴坐标,单位 m +}rm_envelopes_ball_t; +/** + * @brief 包络球参数集合 + * + */ +typedef struct{ + rm_envelopes_ball_t balls[5];///< 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + int size; ///< 包络球数量 + char tool_name[12];///< 控制器中已存在的工具坐标系名称,如果不存在该字段,则为临时设置当前包络参数 +}rm_envelope_balls_list_t; + +/** + * @brief 电子围栏/虚拟墙使能状态参数 + * + */ +typedef struct +{ + bool enable_state; ///< 电子围栏/虚拟墙使能状态,true 代表使能,false 代表禁使能 + int in_out_side; ///< 0-机器人在电子围栏/虚拟墙内部,1-机器人在电子围栏外部 + int effective_region; ///< 0-电子围栏针对整臂区域生效,1-虚拟墙针对末端生效 +}rm_electronic_fence_enable_t; + + +/** + * @brief (UDP主动上报机械臂信息)力传感器数据结构体 + * +*/ +typedef struct { + float force[6]; ///< 当前力传感器原始数据,0.001N或0.001Nm + float zero_force[6]; ///< 当前力传感器系统外受力数据,0.001N或0.001Nm + int coordinate; ///< 系统外受力数据的坐标系,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 +} rm_force_sensor_t; + +/*** + * 扩展关节数据 + * + */ +typedef struct { + float pos; ///< 当前角度 精度 0.001°,单位:° + int current; ///< 当前驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能 + int joint_id; ///< 关节id号 + int mode; ///< 当前升降状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 +} rm_udp_expand_state_t; + +/*** + * 升降机构状态 + * + */ +typedef struct { + int height; ///< 当前升降机构高度,单位:mm,精度:1mm + float pos; ///< 当前角度 精度 0.001°,单位:° + int current; ///< 当前驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能 +} rm_udp_lift_state_t; +/*** + * 灵巧手状态 + * + */ +typedef struct { + int hand_pos[6]; ///< 表示灵巧手位置 + int hand_angle[6]; ///< 表示灵巧手角度 + int hand_force[6]; ///< 表示灵巧手自由度力,单位mN + int hand_state[6]; ///< 表示灵巧手自由度状态,由灵巧手厂商定义状态含义 + int hand_err; ///< 表示灵巧手系统错误,由灵巧手厂商定义错误含义,例如因时状态码如下:1表示有错误,0表示无错误 +} rm_udp_hand_state_t; + +/*** + * + * 轨迹连接配置 + */ +typedef enum{ + RM_TRAJECTORY_DISCONNECT_E = 0, ///<立即规划并执行轨迹,不连接后续轨迹 + RM_TRAJECTORY_CONNECT_E ///<将当前轨迹与下一条轨迹一起规划 +}rm_trajectory_connect_config_e; + +/** + * @brief 机械臂当前状态 + * + */ +typedef enum { + RM_IDLE_E, // 使能但空闲状态 + RM_MOVE_L_E, // move L运动中状态 + RM_MOVE_J_E, // move J运动中状态 + RM_MOVE_C_E, // move C运动中状态 + RM_MOVE_S_E, // move S运动中状态 + RM_MOVE_THROUGH_JOINT_E, // 角度透传状态 + RM_MOVE_THROUGH_POSE_E, // 位姿透传状态 + RM_MOVE_THROUGH_FORCE_POSE_E, // 力控透传状态 + RM_MOVE_THROUGH_CURRENT_E, // 电流环透传状态 + RM_STOP_E, // 急停状态 + RM_SLOW_STOP_E, // 缓停状态 + RM_PAUSE_E, // 暂停状态 + RM_CURRENT_DRAG_E, // 电流环拖动状态 + RM_SENSOR_DRAG_E, // 六维力拖动状态 + RM_TECH_DEMONSTRATION_E // 示教状态 +} rm_udp_arm_current_status_e; + +/*** + * aloha主臂状态 + * + */ +typedef struct { + int io1_state; ///< IO1状态(手柄光电检测),0为按键未触发,1为按键触发。 + int io2_state; ///< IO2状态(手柄光电检测),0为按键未触发,1为按键触发。 +} rm_udp_aloha_state_t; + +/** + * 末端设备基础信息(末端生态协议支持) +*/ +typedef struct{ + char manu[10]; // 设备厂家 + int type; // 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 + char hv[10]; // 硬件版本 + char sv[10]; // 软件版本 + char bv[10]; // boot版本 + int id; // 设备ID + int dof; // 自由度 + int check; // 自检开关 + int bee; // 蜂鸣器开关 + bool force; // 力控支持 + bool touch; // 触觉支持 + int touch_num; // 触觉个数 + int touch_sw; // 触觉开关 + int hand; // 手方向 1 :左手 2: 右手 + int pos_up[12]; // 位置上限,单位:无量纲 + int pos_low[12]; // 位置下限,单位:无量纲 + int angle_up[12]; // 角度上限,单位:0.01度 + int angle_low[12]; // 角度下限,单位:0.01度 + int speed_up[12]; // 速度上限,单位:无量纲 + int speed_low[12]; // 速度下限,单位:无量纲 + int force_up[12]; // 力上限,单位:0.001N + int force_low[12]; // 力下限,单位:0.001N +} rm_plus_base_info_t; +// 单位:无量纲 +/** + * 末端设备实时信息(末端生态协议支持) +*/ +typedef struct{ + int sys_state; // 系统状态:0正常1设备故障 + int dof_state[12]; // 各自由度当前状态:0正在松开1正在闭合2位置到位停止3力控到位停止4触觉到位停止5电流保护停止6发生故障 + int dof_err[12]; // 各自由度错误信息 + int pos[12]; // 各自由度当前位置,单位:无量纲 + int speed[12]; //各自由度当前速度,闭合正,松开负,单位:无量纲 + int angle[12]; // 各自由度当前角度,单位:0.01度 + int current[12]; // 各自由度当前电流,单位:mA + int normal_force[18]; // 自由度触觉三维力的法向力,1-6自由度触觉三维力的法向力*3 + int tangential_force[18]; // 自由度触觉三维力的切向力 + int tangential_force_dir[18]; // 自由度触觉三维力的切向力方向 + uint32_t tsa[12]; // 自由度触觉自接近 + uint32_t tma[12]; // 自由度触觉互接近 + int touch_data[18]; // 触觉传感器原始数据(示例中有,但未显示数据的JSON情况) + int force[12]; //自由度力矩,闭合正,松开负,单位0.001N +} rm_plus_state_info_t; + + +/** + * @brief udp主动上报机械臂信息 + * +*/ +typedef struct +{ + int errCode; ///< 数据解析错误码,-3为数据解析错误,代表推送的数据不完整或格式不正确 + char arm_ip[16]; ///< 推送数据的机械臂的IP地址 + rm_joint_status_t joint_status; ///< 关节状态 + rm_force_sensor_t force_sensor; ///< 力数据(六维力或一维力版本支持) + rm_err_t err; ///< 错误码 + rm_pose_t waypoint; ///< 当前路点信息 + rm_udp_lift_state_t liftState; ///< 升降关节数据 + rm_udp_expand_state_t expandState; ///< 扩展关节数据 + rm_udp_hand_state_t handState; ///< 灵巧手数据 + rm_udp_arm_current_status_e arm_current_status; ///< 机械臂状态 + rm_udp_aloha_state_t aloha_state; ///< aloha主臂状态 + int rm_plus_state; ///< 末端设备状态,0-设备在线,1-表示协议未开启,2-表示协议开启但是设备不在线 + rm_plus_base_info_t plus_base_info; ///< 末端设备基础信息 + rm_plus_state_info_t plus_state_info; ///< 末端设备实时信息 +}rm_realtime_arm_joint_state_t; + +/** + * @brief 逆解参数 + * @ingroup Algo + */ +typedef struct { + float q_in[ARM_DOF]; ///< 上一时刻关节角度,单位° + rm_pose_t q_pose; ///< 目标位姿 + uint8_t flag; ///< 姿态参数类别:0-四元数;1-欧拉角 +} rm_inverse_kinematics_params_t; + +typedef struct { + int result; // 0:成功,1:逆解失败,-1:上一时刻关节角度输入为空或超关节限位,-2:目标位姿四元数不合法, -3:当前机器人非六自由度,当前仅支持六自由度机器人 + int num; // number of solutions + float q_ref[8]; // 参考关节角度,通常是当前关节角度, 单位 ° + float q_solve[8][8]; // 关节角全解, 单位 ° +} rm_inverse_kinematics_all_solve_t; + +/** + * @brief 包络球描述数据结构 +*/ +typedef struct +{ + float radius; // 球体半径(单位:m) + float centrePoint[3]; // 球体中心位置(单位:m,以法兰坐标系为参考坐标系) +} rm_tool_sphere_t; // 工具包络球参数 + + +/** + * @brief 旋转矩阵 + * @ingroup Algo + */ +typedef struct +{ + short irow; + short iline; + float data[4][4]; +} rm_matrix_t; +/** + * @brief 机械臂事件回调函数 + * @ingroup Init_Class + */ +typedef void (*rm_event_callback_ptr)(rm_event_push_data_t data); +/** + * @brief UDP机械臂状态主动上报回调函数 + * @ingroup Init_Class + */ +typedef void (*rm_realtime_arm_state_callback_ptr)(rm_realtime_arm_joint_state_t data); + +/** + * @brief 机械臂基本信息 + * @ingroup Init_Class + */ +typedef struct +{ + uint8_t arm_dof; ///< 机械臂自由度 + rm_robot_arm_model_e arm_model; ///< 机械臂型号 + rm_force_type_e force_type; ///< 末端力传感器版本 + uint8_t robot_controller_version; ///< 机械臂控制器版本,4:四代控制器,3:三代控制器。 +}rm_robot_info_t; + +/** + * @brief 机械臂控制句柄 + * @ingroup Init_Class + */ +typedef struct { + int id; ///< 句柄id,连接成功id大于0,连接失败返回-1 +}rm_robot_handle; + + +typedef struct +{ + float d[8]; //* unit: m + float a[8]; //* unit: m + float alpha[8]; //* unit: ° + float offset[8]; //* unit: ° +} rm_dh_t; + +/** + * @brief 版本号结构体 + * 不超过10个字符 + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct { + char version[10]; +} rm_version_t; + +/** + * @brief 轨迹信息结构体 + */ +typedef struct { + int point_num; ///< 轨迹点数量 + char name[20]; ///< 轨迹名称 + char create_time[20]; ///< 创建时间 +}rm_trajectory_info_t; +/** + * @brief 轨迹列表结构体 + * @ingroup OnlineProgramming + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的轨迹列表长度 + rm_trajectory_info_t tra_list[100]; ///< 返回符合的轨迹列表 +}rm_trajectory_list_t; +/** + * @brief Modbus TCP主站信息结构体 + */ +typedef struct { + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符 + char ip[16]; // TCP主站 IP 地址 + int port; // TCP主站端口号 +}rm_modbus_tcp_master_info_t; +/** + * @brief Modbus TCP主站列表结构体 + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的TCP主站列表长度 + rm_modbus_tcp_master_info_t master_list[100]; ///< 返回符合的TCP主站列表 +}rm_modbus_tcp_master_list_t; + +/** + * @brief Modbus RTU读数据参数结构体 + */ +typedef struct { + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。 + int num; ///< 要读的数据的数量,数据长度不超过109 +}rm_modbus_rtu_read_params_t; +/** + * @brief Modbus RTU写数据结构体 + */ +typedef struct { + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。 + int num; ///< 要写的数据的数量,最大不超过100 + int data[120]; ///< 要写的数据,数据长度不超过100 +}rm_modbus_rtu_write_params_t; + +/** + * @brief Modbus TCP读数据参数结构体 + */ +typedef struct { + int address; // 数据起始地址 + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + int port; // 主机连接的端口号 + int num; // 读取数据数量,最大不超过100 +}rm_modbus_tcp_read_params_t; +/** + * @brief Modbus TCP写数据结构体 + */ +typedef struct { + int address; // 数据起始地址 + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + int port; // 主机连接的端口号 + int num; // 写入数据数量,最大不超过100 + int data[120]; // 写入的数据,数据长度不超过100 +}rm_modbus_tcp_write_params_t; + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h new file mode 100755 index 0000000..90976cf --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h @@ -0,0 +1,773 @@ +// Copyright (c) 2023 RealMan Intelligent Ltd +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/clock.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +#include // 设置非阻塞需要用到的头文件 +#include +#include //使用fd_set结构体时使用。 +#include + +#include "rm_service.h" +#include "rm_define.h" +#include "rm_ros_interfaces/msg/movej.hpp" +#include "rm_ros_interfaces/msg/movel.hpp" +#include "rm_ros_interfaces/msg/movec.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "rm_ros_interfaces/msg/jointteach.hpp" +#include "rm_ros_interfaces/msg/ortteach.hpp" +#include "rm_ros_interfaces/msg/posteach.hpp" +#include "rm_ros_interfaces/msg/setrealtimepush.hpp" +#include "rm_ros_interfaces/msg/softwarebuildinfo.hpp" +#include "rm_ros_interfaces/msg/armsoftversion.hpp" +#include "rm_ros_interfaces/msg/sixforce.hpp" +#include "rm_ros_interfaces/msg/jointerrorcode.hpp" +#include "rm_ros_interfaces/msg/forcepositionmovejoint.hpp" +#include "rm_ros_interfaces/msg/forcepositionmovepose.hpp" +#include "rm_ros_interfaces/msg/setforceposition.hpp" +#include "rm_ros_interfaces/msg/jointpos.hpp" +#include "rm_ros_interfaces/msg/cartepos.hpp" +#include "rm_ros_interfaces/msg/jointerrclear.hpp" +#include "rm_ros_interfaces/msg/gripperset.hpp" +#include "rm_ros_interfaces/msg/gripperpick.hpp" +#include "rm_ros_interfaces/msg/handangle.hpp" +#include "rm_ros_interfaces/msg/handforce.hpp" +#include "rm_ros_interfaces/msg/handposture.hpp" +#include "rm_ros_interfaces/msg/handseq.hpp" +#include "rm_ros_interfaces/msg/handspeed.hpp" +#include "rm_ros_interfaces/msg/armstate.hpp" +#include "rm_ros_interfaces/msg/armoriginalstate.hpp" +#include "rm_ros_interfaces/msg/getallframe.hpp" +#include "rm_ros_interfaces/msg/liftspeed.hpp" +#include "rm_ros_interfaces/msg/liftstate.hpp" +#include "rm_ros_interfaces/msg/liftheight.hpp" +#include "rm_ros_interfaces/msg/handstatus.hpp" +#include "rm_ros_interfaces/msg/armcurrentstatus.hpp" +#include "rm_ros_interfaces/msg/jointcurrent.hpp" +#include "rm_ros_interfaces/msg/jointenflag.hpp" +#include "rm_ros_interfaces/msg/jointposeeuler.hpp" +#include "rm_ros_interfaces/msg/jointspeed.hpp" +#include "rm_ros_interfaces/msg/jointtemperature.hpp" +#include "rm_ros_interfaces/msg/jointvoltage.hpp" +#include "rm_ros_interfaces/msg/jointposcustom.hpp" +#include "rm_ros_interfaces/msg/carteposcustom.hpp" +#include "rm_ros_interfaces/msg/rmplusbase.hpp" +#include "rm_ros_interfaces/msg/rmplusstate.hpp" +#include "rm_ros_interfaces/msg/rmerr.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +// 适配四代控制器新增 +#include "rm_ros_interfaces/msg/robot_info.hpp" +// #include "rm_ros_interfaces/msg/rmversion.hpp" +#include "rm_ros_interfaces/msg/flowchartrunstate.hpp" +#include "rm_ros_interfaces/msg/trajectoryinfo.hpp" +#include "rm_ros_interfaces/msg/trajectorylist.hpp" +#include "rm_ros_interfaces/msg/modbustcpmasterinfo.hpp" +#include "rm_ros_interfaces/msg/modbustcpmasterupdata.hpp" +#include "rm_ros_interfaces/msg/modbustcpmasterlist.hpp" +#include "rm_ros_interfaces/msg/modbustcpreadparams.hpp" +#include "rm_ros_interfaces/msg/modbustcpwriteparams.hpp" +#include "rm_ros_interfaces/msg/modbusrtureadparams.hpp" +#include "rm_ros_interfaces/msg/modbusrtuwriteparams.hpp" +#include "rm_ros_interfaces/msg/programrunstate.hpp" +// #include "rm_ros_interfaces/msg/armsoftversionv3.hpp" +// #include "rm_ros_interfaces/msg/armsoftversionv4.hpp" +#include "rm_ros_interfaces/msg/moveloffset.hpp" +#include "rm_ros_interfaces/msg/jointversion.hpp" +#include "rm_ros_interfaces/msg/stop.hpp" +#include "rm_ros_interfaces/msg/mastername.hpp" +#include "rm_ros_interfaces/msg/getmodbustcpmasterlist.hpp" +#include "rm_ros_interfaces/msg/rs485params.hpp" +#include "rm_ros_interfaces/msg/modbusreaddata.hpp" +#include "rm_ros_interfaces/msg/gettrajectorylist.hpp" +#include "rm_ros_interfaces/msg/sendproject.hpp" +#include "rm_ros_interfaces/msg/toolsoftwareversionv4.hpp" + + +#define RAD_DEGREE 57.295791433 +#define DEGREE_RAD 0.01745 +using namespace std::chrono_literals; +//udp数据处理函数 +// void Udp_RobotStatuscallback(RobotStatus Udp_RM_Callback); +void Udp_Robot_Status_Callback(rm_realtime_arm_joint_state_t data); +//ctrl+c执行程序 +static void my_handler(int sig); +//机械臂型号信息 +int realman_arm; +//tcp ip +char* tcp_ip; +//tcp port +int tcp_port; +//udp hz +int udp_cycle_g = 5; +//arm dof +int arm_dof_g = 6; +// controller verison +int controller_version = 3; +//ctrl+c触发信号 +bool ctrl_flag = false; +// 灵巧手数据发布 +bool udp_hand_g = false; +// 末端设备基础信息发布 +bool rm_plus_base_g = false; +// 末端设备实时信息 +bool rm_plus_state_g = false; +// 连接状态标志 +int connect_state_flag = 0; +//api类 +RM_Service Rm_Api; +//机械臂TCp网络通信套接字 +// SOCKHANDLE m_sockhand = -1; +//机械臂控制句柄 +rm_robot_handle *robot_handle; + +//末端设备基础信息 +typedef struct{ + char manu[10]; // 设备厂家 + int type; // 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 + char hv[10]; // 硬件版本 + char sv[10]; // 软件版本 + char bv[10]; // boot版本 + int id; // 设备ID + int dof; // 自由度 + int check; // 自检开关 + int bee; // 蜂鸣器开关 + bool force; // 力控支持 + bool touch; // 触觉支持 + int touch_num; // 触觉个数 + int touch_sw; // 触觉开关 + int hand; // 手方向 1 :左手 2: 右手 + int pos_up[12]; // 位置上限,单位:无量纲 + int pos_low[12]; // 位置下限,单位:无量纲 + int angle_up[12]; // 角度上限,单位:0.01度 + int angle_low[12]; // 角度下限,单位:0.01度 + int speed_up[12]; // 速度上限,单位:无量纲 + int speed_low[12]; // 速度下限,单位:无量纲 + int force_up[12]; // 力上限,单位:0.001N + int force_low[12]; // 力下限,单位:0.001N +} RM_PLUS_BASE_INFO; + +//末端设备实时信息(末端生态协议支持) +typedef struct +{ + int sys_state; //系统状态 + int dof_state[12]; //各自由度当前状态 + int dof_err[12]; //各自由度错误信息 + int pos[12]; //各自由度当前位置 + int speed[12]; //各自由度当前速度 + int angle[12]; //各自由度当前角度 + int current[12]; //各自由度当前电流 + int normal_force[18]; //自由度触觉三维力的法向力 + int tangential_force[18]; //自由度触觉三维力的切向力 + int tangential_force_dir[18]; //自由度触觉三维力的切向力方向 + uint32_t tsa[12]; //自由度触觉自接近 + uint32_t tma[12]; //自由度触觉互接近 + int touch_data[18]; //触觉传感器原始数据 + int force[12]; //自由度力矩 +} RM_PLUS_STATE_INFO; + +typedef struct +{ + uint8_t err_len; + std::vector err; +} RM_ERR; + +//机械臂状态参数 +typedef struct +{ + float joint[7]; //关节角度 + uint16_t err_flag[7]; //关节错误代码 + uint16_t sys_err; //系统错误代码 + uint16_t arm_err; //机械臂错误代码 + float one_force; //一维力传感器原始数据0.001N或0.001Nm + float six_force[6]; //六维力数据 + float joint_current[7]; //机械臂电流数据 + bool en_flag[7]; //当前关节使能状态 ,1为上使能,0为掉使能 + float joint_position[3]; //当前末端关节位置,精度0.001° + float joint_temperature[7]; //当前关节温度,精度0.001℃ + float joint_voltage[7]; //当前关节电压,精度0.001V + float joint_euler[3]; //欧拉角 + float joint_quat[4]; //四元数 + float zero_force[6]; //当前力传感器系统外受力数据0.001N或0.001Nm + float work_zero_force[6]; //当前工作坐标系下系统受到的外力数据 + float tool_zero_force[6]; //当前该工具坐标系下系统受到的外力数据 + float one_zero_force; //一维力基准坐标系下系统受力数据 + uint16_t control_version; //版本信息 + uint16_t coordinate; //当前六维力传感器的基准坐标 + uint16_t hand_angle[6]; //手指角度数组,范围:0~2000. + uint16_t hand_pos[6]; //手指位置数组,范围:0~1000. + uint16_t hand_state[6]; //手指状态,0正在松开,1正在抓取,2位置到位停止,3力到位停止,5电流保护停止,6电缸堵转停止,7电缸故障停止 + uint16_t hand_force[6]; //灵巧手自由度电流,单位mN + uint16_t hand_err; //灵巧手系统错误,1表示有错误,0表示无错误 + uint16_t arm_current_status; //当前机械臂状态上报, + float joint_speed[7]; //当前关节速度,精度0.02RPM。 + RM_PLUS_STATE_INFO udp_rm_plus_state_info; //末端设备实时信息 + RM_PLUS_BASE_INFO udp_rm_plus_base_info; //末端设备实时信息 + RM_ERR udp_rm_err; +} JOINT_STATE_VALUE; +JOINT_STATE_VALUE Udp_RM_Joint; + +std_msgs::msg::UInt16 sys_err_; //系统错误信息 +std_msgs::msg::UInt16 arm_err_; //机械臂错误信息 +std_msgs::msg::UInt16 arm_coordinate_; //六维力基准坐标系 +sensor_msgs::msg::JointState udp_real_joint_; //关节角度 +geometry_msgs::msg::Pose udp_arm_pose_; //位姿 +rm_ros_interfaces::msg::Sixforce udp_sixforce_; //六维力传感器原始数据 +rm_ros_interfaces::msg::Sixforce udp_zeroforce_; //六维力传感器转化后数据 +rm_ros_interfaces::msg::Sixforce udp_oneforce_; //一维力传感器原始数据 +rm_ros_interfaces::msg::Sixforce udp_onezeroforce_; //一维力传感器转化后数据 +rm_ros_interfaces::msg::Jointerrorcode udp_joint_error_code_; //关节报错数据 +rm_ros_interfaces::msg::Handstatus udp_hand_status_; +rm_ros_interfaces::msg::Armoriginalstate Arm_original_state; //机械臂原始数据(角度+欧拉角) +rm_ros_interfaces::msg::Armstate Arm_state; //机械臂数据(弧度+四元数) +rm_ros_interfaces::msg::Armcurrentstatus udp_arm_current_status_; // +rm_ros_interfaces::msg::Jointcurrent udp_joint_current_; // +rm_ros_interfaces::msg::Jointenflag udp_joint_en_flag_; +rm_ros_interfaces::msg::Jointposeeuler udp_joint_pose_euler_; +rm_ros_interfaces::msg::Jointspeed udp_joint_speed_; +rm_ros_interfaces::msg::Jointtemperature udp_joint_temperature_; +rm_ros_interfaces::msg::Jointvoltage udp_joint_voltage_; +rm_ros_interfaces::msg::Rmplusbase udp_rm_plus_base_; //末端设备基础信息 +rm_ros_interfaces::msg::Rmplusstate udp_rm_plus_state_; //末端设备实时信息 +rm_ros_interfaces::msg::Rmerr udp_rm_err_; //末端设备实时信息 + +class RmArm: public rclcpp::Node +{ +public: + RmArm(); + ~RmArm(); + +/**********************************************初始化需要用到的回调函数***********************************************/ + void Get_Arm_Version(); + void Get_Controller_Version(); //获取版本信息 + void Set_UDP_Configuration(int udp_cycle, int udp_port, int udp_force_coordinate, std::string udp_ip,bool hand, bool rm_plus_base, bool rm_plus_state); //设置udp主动上报配置 + /*******************************运动控制回调函数******************************/ + // void Arm_MoveJ_75_Callback(rm_ros_interfaces::msg::Movej75::SharedPtr msg); //75角度控制 + void Arm_MoveJ_Callback(rm_ros_interfaces::msg::Movej::SharedPtr msg); //角度控制 + void Arm_MoveL_Callback(rm_ros_interfaces::msg::Movel::SharedPtr msg); + void Arm_MoveL_Offset_Callback(rm_ros_interfaces::msg::Moveloffset::SharedPtr msg); + void Arm_MoveC_Callback(rm_ros_interfaces::msg::Movec::SharedPtr msg); //圆弧运动控制 + void Arm_Movej_CANFD_Callback(rm_ros_interfaces::msg::Jointpos::SharedPtr msg); //角度透传控制 + void Arm_Movej_CANFD_Custom_Callback(rm_ros_interfaces::msg::Jointposcustom::SharedPtr msg); //角度透传控制高跟随下可自定义模式 + void Arm_Movep_CANFD_Callback(rm_ros_interfaces::msg::Cartepos::SharedPtr msg); //位姿透传控制 + void Arm_Movep_CANFD_Custom_Callback(rm_ros_interfaces::msg::Carteposcustom::SharedPtr msg); //位姿透传控制高跟随下可自定义模式 + void Arm_MoveJ_P_Callback(rm_ros_interfaces::msg::Movejp::SharedPtr msg); //位姿运动控制 + void Arm_Move_Stop_Callback(const std_msgs::msg::Empty::SharedPtr msg); //轨迹急停控制 + void Arm_Emergency_Stop_Callback(const rm_ros_interfaces::msg::Stop::SharedPtr msg); //设置机械臂急停状态 + /**************************************************************************/ + void Set_Joint_Teach_Callback(rm_ros_interfaces::msg::Jointteach::SharedPtr msg); //关节示教 + void Set_Pos_Teach_Callback(rm_ros_interfaces::msg::Posteach::SharedPtr msg); //位置示教 + void Set_Ort_Teach_Callback(rm_ros_interfaces::msg::Ortteach::SharedPtr msg); //姿态示教 + void Set_Stop_Teach_Callback(const std_msgs::msg::Empty::SharedPtr msg); //停止示教 + + /*******************************主动上报回调函数******************************/ + void Arm_Get_Realtime_Push_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取主动上报配置 + void Arm_Set_Realtime_Push_Callback(const rm_ros_interfaces::msg::Setrealtimepush::SharedPtr msg); //设置主动上报配置参数 + /*******************************力位混合回调函数******************************/ + void Arm_Start_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg); //力位混合开始 + void Arm_Stop_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg); //力位混合结束 + void Arm_Force_Position_Move_Joint_Callback(const rm_ros_interfaces::msg::Forcepositionmovejoint::SharedPtr msg); //力位混合透传(角度) + void Arm_Force_Position_Move_Pose_Callback(const rm_ros_interfaces::msg::Forcepositionmovepose::SharedPtr msg); //力位混合透传(位姿) + void Arm_Set_Force_Postion_Callback(const rm_ros_interfaces::msg::Setforceposition::SharedPtr msg); //使能力位混合透传 + void Arm_Stop_Force_Postion_Callback(const std_msgs::msg::Empty::SharedPtr msg); //结束力位混合透传 + /*******************************坐标系回调函数******************************/ + void Arm_Change_Work_Frame_Callback(const std_msgs::msg::String::SharedPtr msg); //更改工作坐标系 + void Arm_Get_Curr_WorkFrame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询工作坐标系 + void Arm_Get_Current_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询工具坐标系 + void Arm_Get_All_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询所有工具坐标系 + void Arm_Get_All_Work_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询所有工作坐标系 + /*******************************设置工具端电压*********************************/ + void Arm_Set_Tool_Voltage_Callback(const std_msgs::msg::UInt16::SharedPtr msg); + /*******************************清除错误码回调函数****************************/ + void Arm_Set_Joint_Err_Clear_Callback(const rm_ros_interfaces::msg::Jointerrclear::SharedPtr msg); + /*********************************夹爪回调函数******************************/ + void Arm_Set_Gripper_Pick_On_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg); //持续力控夹取 + void Arm_Set_Gripper_Pick_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg); //力控夹取 + void Arm_Set_Gripper_Position_Callback(const rm_ros_interfaces::msg::Gripperset::SharedPtr msg); //移动到固定位置 + /*********************************灵巧手回调函数******************************/ + void Arm_Set_Hand_Posture_Callback(const rm_ros_interfaces::msg::Handposture::SharedPtr msg); //设置灵巧手手势 + void Arm_Set_Hand_Seq_Callback(const rm_ros_interfaces::msg::Handseq::SharedPtr msg); //设置灵巧手动作序列 + void Arm_Set_Hand_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手角度 + void Arm_Set_Hand_Speed_Callback(const rm_ros_interfaces::msg::Handspeed::SharedPtr msg); //设置灵巧手速度 + void Arm_Set_Hand_Force_Callback(const rm_ros_interfaces::msg::Handforce::SharedPtr msg); //设置灵巧手力控 + void Arm_Set_Hand_Follow_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手角度跟随 + void Arm_Set_Hand_Follow_Pos_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手位置跟随 + /*********************************升降机构回调函数******************************/ + void Arm_Set_Lift_Speed_Callback(const rm_ros_interfaces::msg::Liftspeed::SharedPtr msg); //升降机构速度开环控制 + void Arm_Set_Lift_Height_Callback(const rm_ros_interfaces::msg::Liftheight::SharedPtr msg); //升降机构位置闭环控制 + void Arm_Get_Lift_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取升降机构状态 + /*******************************机械臂状态回调函数****************************/ + void Arm_Get_Current_Arm_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); + /*********************************六维力数据清零******************************/ + void Arm_Clear_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg); + /*********************************六维力数据获取******************************/ + void Arm_Get_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg); + /*********************************适配四代控制器******************************/ + /*******************************固件版本回调函数******************************/ + void Arm_Get_Robot_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本 + void Arm_Get_Arm_Software_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本 + void Arm_Get_Joint_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本 + void Arm_Get_Tool_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本 + + void Get_Trajectory_File_List_Callback(const rm_ros_interfaces::msg::Gettrajectorylist::SharedPtr msg); //查询轨迹列表 + void Set_Run_Trajectory_Callback(const std_msgs::msg::String::SharedPtr msg); //开始运行指定轨迹 + void Delete_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg); //删除指定轨迹 + void Save_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg); //保存轨迹到控制机器 + + void Arm_Get_Flowchart_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本 + void Add_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterinfo::SharedPtr msg); //新增Modbus TCP主站 + void Update_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterupdata::SharedPtr msg); //更新Modbus TCP主站 + void Delete_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg); //删除Modbus TCP主站 + void Get_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg); //查询指定modbus主站 + void Get_Modbus_Tcp_Master_List_Callback(const rm_ros_interfaces::msg::Getmodbustcpmasterlist::SharedPtr msg); //查询modbus主站列表 + void Set_Controller_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg); // 设置控制器RS485模式(四代控制器支持) + void Get_Controller_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg); // 查询控制器RS485模式(四代控制器支持) + void Set_Tool_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg); // 设置工具端RS485模式(四代控制器支持) + void Get_Tool_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg); // 查询工具端RS485模式(四代控制器支持) + void Read_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读线圈 + void Write_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg);// Modbus RTU协议写线圈 + void Read_Modbus_RTU_Input_Status_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读离散量输入 + void Read_Modbus_RTU_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读保持寄存器 + void Write_Modbus_RTU_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg);// Modbus RTU协议写保持寄存器 + void Read_Modbus_RTU_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读输入寄存器 + void Read_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读线圈 + void Write_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg);// Modbus TCP协议写线圈 + void Read_Modbus_TCP_Input_Status_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读离散量输入 + void Read_Modbus_TCP_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读保持寄存器 + void Write_Modbus_TCP_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg);// Modbus TCP协议写保持寄存器 + void Read_Modbus_TCP_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读输入寄存器 + + void Send_Project_Callback(const rm_ros_interfaces::msg::Sendproject::SharedPtr msg); //文件下发 + void Get_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询在线编程运行状态 + + + +/***************************************************************end******************************************************/ +private: + // int Arm_Start(void); //TCP连接函数 + // void Arm_Close(); //TCP断连函数 + +/************************************************************变量信息******************************************************/ + std_msgs::msg::Empty::SharedPtr copy; //闲置 + // std_msgs::msg::UInt16 sys_err_; //系统错误信息 + // std_msgs::msg::UInt16 arm_err_; //机械臂错误信息 + // std_msgs::msg::UInt16 arm_coordinate_; //六维力基准坐标系 + // sensor_msgs::msg::JointState udp_real_joint_; //关节角度 + // geometry_msgs::msg::Pose udp_arm_pose_; //位姿 + // rm_ros_interfaces::msg::Sixforce udp_sixforce_; //六维力传感器原始数据 + // rm_ros_interfaces::msg::Sixforce udp_zeroforce_; //六维力传感器转化后数据 + // rm_ros_interfaces::msg::Sixforce udp_oneforce_; //一维力传感器原始数据 + // rm_ros_interfaces::msg::Sixforce udp_onezeroforce_; //一维力传感器转化后数据 + // rm_ros_interfaces::msg::Jointerrorcode udp_joint_error_code_; //关节报错数据 + // rm_ros_interfaces::msg::Armoriginalstate Arm_original_state; //机械臂原始数据(角度+欧拉角) + // rm_ros_interfaces::msg::Armstate Arm_state; //机械臂数据(弧度+四元数) + + /****************************************udp主动上报配置查询发布器*************************************/ + rclcpp::Publisher::SharedPtr Get_Realtime_Push_Result; + /****************************************udp主动上报配置查询订阅器*************************************/ + rclcpp::Subscription::SharedPtr Get_Realtime_Push_Cmd; + /******************************************udp主动上报配置发布器***************************************/ + rclcpp::Publisher::SharedPtr Set_Realtime_Push_Result; + /******************************************udp主动上报配置发布器***************************************/ + rclcpp::Subscription::SharedPtr Set_Realtime_Push_Cmd; + /**********************************************************end******************************************************/ + + /********************************************************运动配置******************************************************/ + /****************************************MoveJ运动控制结果发布器*************************************/ + rclcpp::Publisher::SharedPtr MoveJ_Cmd_Result; + /******************************************75MoveJ运动控制订阅器***************************************/ + // rclcpp::Subscription::SharedPtr MoveJ_75_Cmd; + /******************************************MoveJ运动控制订阅器***************************************/ + rclcpp::Subscription::SharedPtr MoveJ_Cmd; + /****************************************MoveL运动控制结果发布器*************************************/ + rclcpp::Publisher::SharedPtr MoveL_Cmd_Result; + rclcpp::Publisher::SharedPtr MoveL_offset_Cmd_Result; + /*******************************************MoveL运动控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr MoveL_Cmd; + rclcpp::Subscription::SharedPtr MoveL_offset_Cmd; + /****************************************MoveC运动控制结果发布器*************************************/ + rclcpp::Publisher::SharedPtr MoveC_Cmd_Result; + /*******************************************MoveC运动控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr MoveC_Cmd; + /*******************************************角度透传运动控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr Movej_CANFD_Cmd; + rclcpp::Subscription::SharedPtr Movej_CANFD_Custom_Cmd; + /*******************************************角度透传运动控制订阅器*************************************/ + // rclcpp::Subscription::SharedPtr Movej_CANFD_75_Cmd; + /*******************************************位姿透传运动控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr Movep_CANFD_Cmd; + rclcpp::Subscription::SharedPtr Movep_CANFD_Custom_Cmd; + /****************************************MoveJ_P运动控制结果发布器*************************************/ + rclcpp::Publisher::SharedPtr MoveJ_P_Cmd_Result; + /*******************************************MoveJ_P运动控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr MoveJ_P_Cmd; + /********************************************轨迹急停结果发布器*****************************************/ + rclcpp::Publisher::SharedPtr Move_Stop_Cmd_Result; + rclcpp::Publisher::SharedPtr Arm_Emergency_Stop_Cmd_Result; + /***********************************************轨迹急停控制订阅器*************************************/ + rclcpp::Subscription::SharedPtr Move_Stop_Cmd; + rclcpp::Subscription::SharedPtr Arm_Emergency_Stop_Cmd; + /********************************************************end******************************************************/ + + /*******************************************************关节示教***************************************************/ + /****************************************关节示教结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Set_Joint_Teach_Cmd_Result; + /*******************************************关节示教订阅器*************************************/ + rclcpp::Subscription::SharedPtr Set_Joint_Teach_Cmd; + /****************************************位置示教结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Set_Pos_Teach_Cmd_Result; + /*******************************************位置示教订阅器*************************************/ + rclcpp::Subscription::SharedPtr Set_Pos_Teach_Cmd; + /****************************************姿态示教结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Set_Ort_Teach_Cmd_Result; + /*******************************************姿态示教订阅器*************************************/ + rclcpp::Subscription::SharedPtr Set_Ort_Teach_Cmd; + /****************************************停止示教结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Set_Stop_Teach_Cmd_Result; + /*******************************************停止示教订阅器*************************************/ + rclcpp::Subscription::SharedPtr Set_Stop_Teach_Cmd; + /********************************************************end******************************************************/ + + /********************************************************适配四代控制器新增***************************************************/ + /********************************************************固件版本***************************************************/ + /*************************************************查询固件版本发布器****************************************/ + // rclcpp::Publisher::SharedPtr Get_Arm_Software_Version_Result_v3; + // rclcpp::Publisher::SharedPtr Get_Arm_Software_Version_Result_v4; + rclcpp::Publisher::SharedPtr Get_Arm_Software_Version_Result; + rclcpp::Subscription::SharedPtr Get_Arm_Software_Version_Cmd; + rclcpp::Publisher::SharedPtr Get_Robot_Info_Result; + rclcpp::Subscription::SharedPtr Get_Robot_Info_Cmd; + rclcpp::Publisher::SharedPtr Get_Joint_Software_Version_Result; + rclcpp::Subscription::SharedPtr Get_Joint_Software_Version_Cmd; + rclcpp::Publisher::SharedPtr Get_Tool_Software_Version_Result; + rclcpp::Subscription::SharedPtr Get_Tool_Software_Version_Cmd; + rclcpp::Publisher::SharedPtr Get_Flowchart_Program_Run_State_Result; + rclcpp::Subscription::SharedPtr Get_Flowchart_Program_Run_State_Cmd; + /*************************************************轨迹列表相关接口****************************************/ + rclcpp::Publisher::SharedPtr Get_Trajectory_File_List_Result; + rclcpp::Subscription::SharedPtr Get_Trajectory_File_List_Cmd; + rclcpp::Publisher::SharedPtr Set_Run_Trajectory_Result; + rclcpp::Subscription::SharedPtr Set_Run_Trajectory_Cmd; + rclcpp::Publisher::SharedPtr Delete_Trajectory_File_Result; + rclcpp::Subscription::SharedPtr Delete_Trajectory_File_Cmd; + rclcpp::Publisher::SharedPtr Save_Trajectory_File_Result; + rclcpp::Subscription::SharedPtr Save_Trajectory_File_Cmd; + + /*************************************************Modbus相关接口****************************************/ + /*************************************************新增Modbus TCP主站****************************************/ + rclcpp::Publisher::SharedPtr Add_Modbus_Tcp_Master_Result; + rclcpp::Subscription::SharedPtr Add_Modbus_Tcp_Master_Cmd; + /*************************************************更新Modbus TCP主站****************************************/ + rclcpp::Publisher::SharedPtr Update_Modbus_Tcp_Master_Result; + rclcpp::Subscription::SharedPtr Update_Modbus_Tcp_Master_Cmd; + /*************************************************删除Modbus TCP主站****************************************/ + rclcpp::Publisher::SharedPtr Delete_Modbus_Tcp_Master_Result; + rclcpp::Subscription::SharedPtr Delete_Modbus_Tcp_Master_Cmd; + /*************************************************查询指定modbus主站****************************************/ + rclcpp::Publisher::SharedPtr Get_Modbus_Tcp_Master_Result; + rclcpp::Subscription::SharedPtr Get_Modbus_Tcp_Master_Cmd; + /*************************************************查询modbus主站列表****************************************/ + rclcpp::Publisher::SharedPtr Get_Modbus_Tcp_Master_List_Result; + rclcpp::Subscription::SharedPtr Get_Modbus_Tcp_Master_List_Cmd; + /*************************************************设置控制器RS485模式(四代控制器支持)****************************************/ + rclcpp::Publisher::SharedPtr Set_Controller_RS485_Mode_Result; + rclcpp::Subscription::SharedPtr Set_Controller_RS485_Mode_Cmd; + /*************************************************查询控制器RS485模式(四代控制器支持)****************************************/ + rclcpp::Publisher::SharedPtr Get_Controller_RS485_Mode_v4_Result; + rclcpp::Subscription::SharedPtr Get_Controller_RS485_Mode_v4_Cmd; + /*************************************************设置工具端RS485模式(四代控制器支持)****************************************/ + rclcpp::Publisher::SharedPtr Set_Tool_RS485_Mode_Result; + rclcpp::Subscription::SharedPtr Set_Tool_RS485_Mode_Cmd; + /*************************************************查询工具端RS485模式(四代控制器支持)****************************************/ + rclcpp::Publisher::SharedPtr Get_Tool_RS485_Mode_v4_Result; + rclcpp::Subscription::SharedPtr Get_Tool_RS485_Mode_v4_Cmd; + + + /*************************************************Modbus RTU协议读线圈****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_RTU_Coils_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_RTU_Coils_Cmd; + /*************************************************Modbus RTU协议写线圈****************************************/ + rclcpp::Publisher::SharedPtr Write_Modbus_RTU_Coils_Result; + rclcpp::Subscription::SharedPtr Write_Modbus_RTU_Coils_Cmd; + /*************************************************Modbus RTU协议读离散量输入****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_RTU_Input_Status_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_RTU_Input_Status_Cmd; + /*************************************************Modbus RTU协议读保持寄存器****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_RTU_Holding_Registers_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_RTU_Holding_Registers_Cmd; + /*************************************************Modbus RTU协议写保持寄存器****************************************/ + rclcpp::Publisher::SharedPtr Write_Modbus_RTU_Registers_Result; + rclcpp::Subscription::SharedPtr Write_Modbus_RTU_Registers_Cmd; + /*************************************************Modbus RTU协议读输入寄存器****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_RTU_Input_Registers_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_RTU_Input_Registers_Cmd; + + /*************************************************Modbus TCP协议读线圈****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_TCP_Coils_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_TCP_Coils_Cmd; + /*************************************************Modbus TCP协议写线圈****************************************/ + rclcpp::Publisher::SharedPtr Write_Modbus_TCP_Coils_Result; + rclcpp::Subscription::SharedPtr Write_Modbus_TCP_Coils_Cmd; + /*************************************************Modbus TCP协议读离散量输入****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_TCP_Input_Status_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_TCP_Input_Status_Cmd; + /*************************************************Modbus TCP协议读保持寄存器****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_TCP_Holding_Registers_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_TCP_Holding_Registers_Cmd; + /*************************************************Modbus TCP协议写保持寄存器****************************************/ + rclcpp::Publisher::SharedPtr Write_Modbus_TCP_Registers_Result; + rclcpp::Subscription::SharedPtr Write_Modbus_TCP_Registers_Cmd; + /*************************************************Modbus TCP协议读输入寄存器****************************************/ + rclcpp::Publisher::SharedPtr Read_Modbus_TCP_Input_Registers_Result; + rclcpp::Subscription::SharedPtr Read_Modbus_TCP_Input_Registers_Cmd; + + /*************************************************文件下发****************************************/ + rclcpp::Publisher::SharedPtr Send_Project_Result; + rclcpp::Subscription::SharedPtr Send_Project_Cmd; + /*************************************************查询在线编程运行状态****************************************/ + rclcpp::Publisher::SharedPtr Get_Program_Run_State_Result; + rclcpp::Subscription::SharedPtr Get_Program_Run_State_Cmd; + + /*************************************************适配四代控制器新增 end****************************************/ + /********************************************************end******************************************************/ + + /*************************************************************力位混合**************************************************/ + /****************************************开启力位混合透传结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Start_Force_Position_Move_Result; + /***********************************************开启力位混合订阅器************************************************/ + rclcpp::Subscription::SharedPtr Start_Force_Position_Move_Cmd; + /****************************************关闭力位混合透传结果发布器*************************************/ + rclcpp::Publisher::SharedPtr Stop_Force_Position_Move_Result; + /***********************************************关闭力位混合订阅器************************************************/ + rclcpp::Subscription::SharedPtr Stop_Force_Position_Move_Cmd; + /********************************************设置力位混合控制结果发布器**************************************/ + rclcpp::Publisher::SharedPtr Set_Force_Postion_Result; + /************************************************设置力位混合控制************************************************/ + rclcpp::Subscription::SharedPtr Set_Force_Postion_Cmd; + /********************************************结束力位混合控制结果发布器*******************************************/ + rclcpp::Publisher::SharedPtr Stop_Force_Postion_Result; + /************************************************结束力位混合控制************************************************/ + rclcpp::Subscription::SharedPtr Stop_Force_Postion_Cmd; + + /**************************************************75力位混合角度透传订阅器***************************************/ + // rclcpp::Subscription::SharedPtr Force_Position_Move_Joint_75_Cmd; + /**************************************************力位混合角度透传订阅器***************************************/ + rclcpp::Subscription::SharedPtr Force_Position_Move_Joint_Cmd; + /***********************************************力位混合位姿透传订阅器*********************************************/ + rclcpp::Subscription::SharedPtr Force_Position_Move_Pose_Cmd; + /**********************************************************************end************************************************************/ + + /**************************************************************坐标系指令发布器**********************************************************/ + /****************************************切换工作坐标系发布器*************************************/ + rclcpp::Publisher::SharedPtr Change_Work_Frame_Result; + /*****************************************切换工作坐标系订阅器************************************/ + rclcpp::Subscription::SharedPtr Change_Work_Frame_Cmd; + /****************************************获取工作坐标系发布器*************************************/ + rclcpp::Publisher::SharedPtr Get_Curr_WorkFrame_Result; + /*****************************************获取工作坐标系订阅器************************************/ + rclcpp::Subscription::SharedPtr Get_Curr_WorkFrame_Cmd; + /****************************************获取工具坐标系发布器*************************************/ + rclcpp::Publisher::SharedPtr Get_Current_Tool_Frame_Result; + /*****************************************获取工具坐标系订阅器************************************/ + rclcpp::Subscription::SharedPtr Get_Current_Tool_Frame_Cmd; + /****************************************获取所有工具坐标系发布器**********************************/ + rclcpp::Publisher::SharedPtr Get_All_Tool_Frame_Result; + /****************************************获取所有工具坐标系订阅器**********************************/ + rclcpp::Subscription::SharedPtr Get_All_Tool_Frame_Cmd; + /****************************************获取所有工作坐标系发布器**********************************/ + rclcpp::Publisher::SharedPtr Get_All_Work_Frame_Result; + /****************************************获取所有工作坐标系订阅器**********************************/ + rclcpp::Subscription::SharedPtr Get_All_Work_Frame_Cmd; + /*****************************************************************end******************************************************************/ + + /****************************************机械臂工具端电源输出发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Tool_Voltage_Result; + /****************************************机械臂工具端电源输出订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Tool_Voltage_Cmd; + + /****************************************清除关节错误代码结果发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Joint_Err_Clear_Result; + /******************************************清除关节错误代码订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Joint_Err_Clear_Cmd; + +/**************************************************************末端工具-手爪控制**********************************************************/ + /****************************************手爪持续力控夹取结果发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Gripper_Pick_On_Result; + /******************************************手爪持续力控夹取订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Gripper_Pick_On_Cmd; + /******************************************手爪力控夹取结果发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Gripper_Pick_Result; + /*********************************************手爪力控夹取订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Gripper_Pick_Cmd; + /****************************************手爪到达指定位置结果发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Gripper_Position_Result; + /******************************************手爪到达指定位置夹取订阅器*********************************/ + rclcpp::Subscription::SharedPtr Set_Gripper_Position_Cmd; +/*****************************************************************end******************************************************************/ + +/**************************************************************末端工具-五指灵巧手控制******************************************************/ + /****************************************设置灵巧手手势序号发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Posture_Result; + /****************************************设置灵巧手手势序号订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Posture_Cmd; + /**************************************设置灵巧手动作序列序号发布器*********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Seq_Result; + /**************************************设置灵巧手动作序列序号订阅器*********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Seq_Cmd; + /****************************************设置灵巧手角度结果发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Angle_Result; + /*******************************************设置灵巧手角度订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Angle_Cmd; + /****************************************设置灵巧手关节速度发布器**********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Speed_Result; + /****************************************设置灵巧手关节速度订阅器**********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Speed_Cmd; + /**************************************设置灵巧手各关节力阈值发布器*********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Force_Result; + /***************************************设置灵巧手各关节力阈值订阅器********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Force_Cmd; + /**************************************设置灵巧手各关节角度跟随结果发布器*********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Follow_Angle_Result; + /***************************************设置灵巧手各关节角度设置订阅器********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Follow_Angle_Cmd; + /**************************************设置灵巧手各关节位置跟随结果发布器*********************************/ + rclcpp::Publisher::SharedPtr Set_Hand_Follow_Pos_Result; + /***************************************设置灵巧手各关节位置跟随订阅器********************************/ + rclcpp::Subscription::SharedPtr Set_Hand_Follow_Pos_Cmd; +/*****************************************************************end******************************************************************/ + +/********************************************************************升降机构***********************************************************/ + /******************************************设置升降机构速度发布器****************Publisher*****************/ + rclcpp::Publisher::SharedPtr Set_Lift_Speed_Result; + /*******************************************设置升降机构速度订阅器********************************/ + rclcpp::Subscription::SharedPtr Set_Lift_Speed_Cmd; + /****************************************设置升降机构高度发布器*********************************/ + rclcpp::Publisher::SharedPtr Set_Lift_Height_Result; + /***************************************设置升降机构高度订阅器********************************/ + rclcpp::Subscription::SharedPtr Set_Lift_Height_Cmd; + /****************************************获取升降机构状态发布器*********************************/ + rclcpp::Publisher::SharedPtr Get_Lift_State_Result; + /***************************************获取升降机构状态订阅器********************************/ + rclcpp::Subscription::SharedPtr Get_Lift_State_Cmd; +/********************************************************************end***********************************************************/ + + /**************************************获取机械臂当前状态发布器*************************************/ + rclcpp::Publisher::SharedPtr Get_Current_Arm_Original_State_Result; + /**************************************获取机械臂当前状态发布器*************************************/ + rclcpp::Publisher::SharedPtr Get_Current_Arm_State_Result; + /***************************************获取机械臂当前状态订阅器************************************/ + rclcpp::Subscription::SharedPtr Get_Current_Arm_State_Cmd; + +/********************************************************************六维力***********************************************************/ + /****************************************六维力数据清零发布器***************************************/ + rclcpp::Publisher::SharedPtr Clear_Force_Data_Result; + /******************************************六维力数据清零订阅器*************************************/ + rclcpp::Subscription::SharedPtr Clear_Force_Data_Cmd; + /********************************************六维力数据获取发布器****************************************/ + rclcpp::Publisher::SharedPtr Get_Force_Data_Result; + rclcpp::Publisher::SharedPtr Get_Zero_Force_Result; + rclcpp::Publisher::SharedPtr Get_Work_Zero_Result; + rclcpp::Publisher::SharedPtr Get_Tool_Zero_Result; + /******************************************六维力数据获取订阅器*************************************/ + rclcpp::Subscription::SharedPtr Get_Force_Data_Cmd; +/********************************************************************end***********************************************************/ + + std::string arm_ip_ = "192.168.1.188"; + std::string udp_ip_ = "192.168.1.10"; + std::string arm_type_ = "RM_75"; + + + int tcp_port_ = 8081; + int udp_port_ = 9501; + int arm_dof_ = 7; //机械臂自由度 + int udp_cycle_ = 5; //udp主动上报周期(ms) + int udp_force_coordinate_ = 0; //udp主动上报系统六维力参考坐标系 + bool udp_hand_ = false; + bool udp_rm_plus_base_ = false; //末端设备基础信息udp发布 + bool udp_rm_plus_state_ = false; //末端设备状态信息udp发布 + int trajectory_mode_ = 0; + int radio_ = 50; + std::vector arm_joints; + + rclcpp::CallbackGroup::SharedPtr callback_group_sub1_; + rclcpp::CallbackGroup::SharedPtr callback_group_sub2_; + rclcpp::CallbackGroup::SharedPtr callback_group_sub3_; + rclcpp::CallbackGroup::SharedPtr callback_group_sub4_; + rclcpp::CallbackGroup::SharedPtr callback_group_sub5_; +}; + +class UdpPublisherNode : public rclcpp::Node +{ +public: + UdpPublisherNode(); + /*******************************主动上报定时器数据处理回调函数**************************/ + void udp_timer_callback(); + void heart_timer_callback(); + bool read_data(); + +private: + rclcpp::CallbackGroup::SharedPtr callback_group_time1_; + rclcpp::CallbackGroup::SharedPtr callback_group_time2_; + rclcpp::CallbackGroup::SharedPtr callback_group_time3_; + rclcpp::TimerBase::SharedPtr Udp_Timer; //UDP定时器 + rclcpp::TimerBase::SharedPtr Heart_Timer; //心跳定时器,检查断开情况 + /*****************************************************UDP数据发布话题************************************************/ + rclcpp::Publisher::SharedPtr Joint_Position_Result; //关节当前状态发布器 + rclcpp::Publisher::SharedPtr Arm_Position_Result; //末端位姿当前状态发布器 + rclcpp::Publisher::SharedPtr Six_Force_Result; //六维力发布器 + rclcpp::Publisher::SharedPtr Six_Zero_Force_Result; //六维力目标坐标系下系统受力发布器 + rclcpp::Publisher::SharedPtr One_Force_Result; //一维力发布器 + rclcpp::Publisher::SharedPtr One_Zero_Force_Result; //一维力目标坐标系下系统受力发布器 + rclcpp::Publisher::SharedPtr Joint_Error_Code_Result; //关节报错信息发布器 + // rclcpp::Publisher::SharedPtr Sys_Err_Result; //系统报错发布器 + rclcpp::Publisher::SharedPtr Rm_Err_Result; //机械臂报错发布器 + rclcpp::Publisher::SharedPtr Arm_Coordinate_Result; //力传感器基准坐标发布器 + rclcpp::Publisher::SharedPtr Hand_Status_Result; //灵巧手数据发布器 + rclcpp::Publisher::SharedPtr Rm_Plus_Base_Result; //末端设备基础信息udp主动上报发布器 + rclcpp::Publisher::SharedPtr Rm_Plus_State_Result; //末端设备实时信息udp主动上报发布器 + rclcpp::Publisher::SharedPtr Arm_Current_Status_Result; //机械臂当前状态发布器 + rclcpp::Publisher::SharedPtr Joint_Current_Result; //关节当前电流发布器 + rclcpp::Publisher::SharedPtr Joint_En_Flag_Result; //关节使能状态布器 + rclcpp::Publisher::SharedPtr Joint_Pose_Euler_Result; //末端位姿欧拉角形式发布器 + rclcpp::Publisher::SharedPtr Joint_Speed_Result; //关节速度发布器 + rclcpp::Publisher::SharedPtr Joint_Temperature_Result; //关节温度发布器 + rclcpp::Publisher::SharedPtr Joint_Voltage_Result; //关节电压发布器 + int connect_state = 0; //网络连接状态 + int come_time = 0; + struct sockaddr_in clientAddr; + socklen_t clientAddrLen = sizeof(clientAddr); + char udp_socket_buffer[1000]; + +}; + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface.h new file mode 100755 index 0000000..4c36968 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface.h @@ -0,0 +1,4517 @@ +/** + * @file rm_interface.h + * @brief 该文档声明了机械臂所有操作接口 + * @author aisha + * @version 0.1.0 + * @date 2024.4.20 + * @copyright 睿尔曼智能科技有限公司 + */ + +#ifndef RM_FUNCTION_H +#define RM_FUNCTION_H + +#include "rm_define.h" +#include "rm_interface_global.h" +#include "rm_version.h" +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @defgroup Init_Class 连接机械臂 + * + * 此模块为API及机械臂初始化相关接口,包含API版本号查询、API初始化、连接/断开机械臂、日志设置、 + * 机械臂仿真/真实模式设置、机械臂信息获取、运动到位信息及机械臂实时状态信息回调函数注册等 + * @{ + */ +/** + * @brief 查询sdk版本号 + * @return char* 返回版本号 + * @code + * char *version = rm_api_version(); + * printf("api version: %s\n", version); + * @endcode + */ +RM_INTERFACE_EXPORT char* rm_api_version(void); +/** + * @brief 初始化线程模式 + * + * @param mode RM_SINGLE_MODE_E:单线程模式,单线程非阻塞等待数据返回; + * RM_DUAL_MODE_E:双线程模式,增加接收线程监测队列中的数据; + * RM_TRIPLE_MODE_E:三线程模式,在双线程模式基础上增加线程监测UDP接口数据; + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 创建线程失败。查看日志以获取具体错误 + */ +RM_INTERFACE_EXPORT int rm_init(rm_thread_mode_e mode); + +/** + * @brief 关闭所有连接,销毁所有线程 + * + * @return int 函数执行的状态码。 + - 0: 成功。 + */ +RM_INTERFACE_EXPORT int rm_destory(void); + +/** + * @brief 日志打印配置 + * + * @param LogCallback 日志打印回调函数 + * @param level 日志打印等级,0:debug级别,1:info级别,2:warn:级别,3:error级别 + */ +RM_INTERFACE_EXPORT void rm_set_log_call_back(void (*LogCallback)(const char* message, va_list args),int level); + +/** + * @brief 保存日志到文件 + * + * @param path 日志保存文件路径 + */ +RM_INTERFACE_EXPORT void rm_set_log_save(const char* path); + +/** + * @brief 设置全局超时时间 + * + * @param timeout 接收控制器返回指令超时时间,多数接口默认超时时间为500ms,单位ms + */ +RM_INTERFACE_EXPORT void rm_set_timeout(int timeout); + +/** + * @brief 创建一个机械臂,用于实现对该机械臂的控制 + * + * @param ip 机械臂的ip地址 + * @param port 机械臂的端口号 + * @return rm_robot_handle* 创建成功后,返回机械臂控制句柄,连接成功句柄id大于0,连接失败句柄id返回-1,达到最大连接数5创建失败返回空 + */ +RM_INTERFACE_EXPORT rm_robot_handle *rm_create_robot_arm(const char *ip,int port); + +/** + * @brief 手动设置机械臂自由度 + * + * @param handle 机械臂控制句柄 + * @param dof 机械臂自由度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 设置失败,自由度设置不合理(负数或者大于10)。 + */ +RM_INTERFACE_EXPORT int rm_set_robot_dof(rm_robot_handle *handle, int dof); + +/** + * @brief 根据句柄删除机械臂 + * + * @param handle 需要删除的机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + */ +RM_INTERFACE_EXPORT int rm_delete_robot_arm(rm_robot_handle *handle); +/** + * @brief 机械臂仿真/真实模式设置 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真模式 1:真实模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_run_mode(rm_robot_handle *handle, int mode); +/** + * @brief 机械臂仿真/真实模式获取 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真模式 1:真实模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_run_mode(rm_robot_handle *handle,int *mode); +/** + * @brief 获取机械臂基本信息 + * + * @param handle 机械臂控制句柄 + * @param robot_info 存放机械臂基本信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 获取到的机械臂基本信息非法,检查句柄是否已被删除。 + */ +RM_INTERFACE_EXPORT int rm_get_robot_info(rm_robot_handle *handle, rm_robot_info_t *robot_info); +/** + * @brief 机械臂事件回调函数注册 + * @details 当机械臂返回运动到位指令或者文件运行结束指令时会有数据返回 + * @attention 单线程无法使用该函数获取到位信息 + * @param handle 机械臂控制句柄 + * @param event_callback 机械臂事件回调函数,该回调函数接收rm_event_push_data_t类型的数据作为参数,没有返回值。 + */ +RM_INTERFACE_EXPORT void rm_get_arm_event_call_back(rm_event_callback_ptr event_callback); +/** + * @brief UDP机械臂状态主动上报信息回调注册 + * + * @param handle 机械臂控制句柄 + * @param realtime_callback 机械臂状态信息回调函数 + */ +RM_INTERFACE_EXPORT void rm_realtime_arm_state_call_back(rm_realtime_arm_state_callback_ptr realtime_callback); +/** @} */ // 结束初始化组的定义 +/** + * @defgroup Joint_Config 关节配置 + * + * 对机械臂的关节参数进行设置,如果关节发生错误,则无法修改关节参数,必须先清除关节错误代码。另外设置关节之前, + * 必须先将关节掉使能,否则会设置不成功。 + * 关节所有参数在修改完成后,会自动保存到关节 Flash,立即生效,之后关节处于掉使能状态,修改完参数后必须 + * 发送指令控制关节上使能。 + * @attention 睿尔曼机械臂在出厂前所有参数都已经配置到最佳状态,一般不建议用户修改关节的底层参数。若用户确需修改,首先 + * 应使机械臂处于非使能状态,然后再发送修改参数指令,参数设置成功后,发送关节恢复使能指令。需要注意的是,关节恢复 + * 使能时,用户需要保证关节处于静止状态,以免上使能过程中关节发生报错。关节正常上使能后,用户方可控制关节运动。 + * @{ + */ +/** + * @brief 设置关节最大速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节最大速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节使能状态 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param en_state 1:上使能 0:掉使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_en_state(rm_robot_handle *handle,int joint_num,int en_state); +/** + * @brief 设置关节零位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_zero_pos(rm_robot_handle *handle,int joint_num); +/** + * @brief 清除关节错误代码 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_clear_err(rm_robot_handle *handle,int joint_num); +/** + * @brief 一键设置关节限位 + * + * @param handle 机械臂句柄 + * @param limit_mode 1-正式模式,各关节限位为规格参数中的软限位和硬件限位 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_joint_limit(rm_robot_handle *handle,int limit_mode); +/** + * @brief 查询关节最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节(驱动器)最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节(驱动器)最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节(驱动器)最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节(驱动器)最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节使能状态 + * + * @param handle 机械臂句柄 + * @param en_state 关节1~7使能状态数组,1-使能状态,0-掉使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_en_state(rm_robot_handle *handle,uint8_t *en_state); +/** + * @brief 查询关节错误代码 + * + * @param handle 机械臂句柄 + * @param err_flag 反馈关节错误代码,错误码请参见 \ref robotic_error + * @param brake_state 反馈关节抱闸状态,1 代表抱闸未打开,0 代表抱闸已打开 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_err_flag(rm_robot_handle *handle,uint16_t *err_flag,uint16_t *brake_state); +/** @} */ // 结束关节配置组的定义 + +/** + * @defgroup ArmTipVelocityParameters 机械臂末端参数配置 + * + * 机械臂末端运动参数设置及获取 + * @{ + */ +/** + * @brief 设置机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端参数为默认值 + * + * @param handle 机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_tcp_init(rm_robot_handle *handle); +/** + * @brief 设置机械臂动力学碰撞检测等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 存放碰撞等级值,数据为0-8,0-无碰撞检测,8-碰撞检测最灵敏 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_collision_state(rm_robot_handle *handle,int collision_stage); +/** + * @brief 查询碰撞防护等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级,范围:0~8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_collision_stage(rm_robot_handle *handle,int *collision_stage); +/** + * @brief 获取机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 获取机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 设置DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data(rm_robot_handle *handle, rm_dh_t dh); +/** + * @brief 获取DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_DH_data(rm_robot_handle *handle, rm_dh_t *dh); +/** + * @brief 恢复机械臂默认 DH 参数 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data_default(rm_robot_handle *handle); +/** @} */ // 结束组的定义 +/** + * @defgroup ToolCoordinateConfig 工具坐标系配置 + * + * 工具坐标系标定、切换、删除、修改、查询及工具包络参数等管理 + * @{ + */ +/** + * @brief 六点法自动设置工具坐标系 标记点位 + * + * @param handle 机械臂控制句柄 + * @param point_num 1~6代表6个标定点 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_tool_frame(rm_robot_handle *handle,int point_num); +/** + * @brief 六点法自动设置工具坐标系 提交 + * + * @param handle 机械臂控制句柄 + * @param name 工具坐标系名称,不能超过十个字节。 + * @param payload 新工具执行末端负载重量 单位kg + * @param x 新工具执行末端负载位置 位置x 单位m + * @param y 新工具执行末端负载位置 位置y 单位m + * @param z 新工具执行末端负载位置 位置z 单位m + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_generate_auto_tool_frame(rm_robot_handle *handle, const char *name,float payload,float x,float y,float z); +/** + * @brief 手动设置工具坐标系 + * + * @param handle 机械臂句柄 + * @param frame 新工具坐标系参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 可能情况:要设置的坐标系名称已存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 切换当前工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 目标工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。可能情况:切换的坐标系不存在 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 删除指定工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 修改指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame 要修改的工具坐标系参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 获取所有工具坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工具坐标系名称字符数组 + * @param len 返回的工具坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_tool_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工具坐标系名称 + * @param frame 返回的工具参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。可能情况:查询的工具坐标系不存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_tool_frame(rm_robot_handle *handle, const char *name, rm_frame_t *frame); +/** + * @brief 获取当前工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param tool_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_tool_frame(rm_robot_handle *handle, rm_frame_t *tool_frame); +/** + * @brief 设置工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_envelope(rm_robot_handle *handle, rm_envelope_balls_list_t envelope); +/** + * @brief 获取工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param tool_name 控制器中已存在的工具坐标系名称 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回获取失败,可能情况:获取的工具坐标系不存在。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_envelope(rm_robot_handle *handle, const char* tool_name, rm_envelope_balls_list_t *envelope); +/** @} */ // 结束组的定义 + +/** + * @defgroup WorkCoordinateConfig 工作坐标系配置 + * + * 工作坐标系标定、切换、删除、修改、查询等管理 + * @{ + */ +/** + * @brief 三点法自动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param workname 工作坐标系名称,不能超过十个字节。 + * @param point_num 1~3代表3个标定点,依次为原点、X轴一点、Y轴一点,4代表生成坐标系。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_work_frame(rm_robot_handle *handle,const char *workname, int point_num); +/** + * @brief 手动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 工作坐标系名称,不能超过十个字节。 + * @param pose 新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 切换当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 目标工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 删除指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 要删除的工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 修改指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 指定工具坐标系名称 + * @param pose 更新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_work_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工作坐标系名称 + * @param pose 获取到的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。例如:查询的工具坐标系不存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_work_frame(rm_robot_handle *handle, const char *name, rm_pose_t *pose); +/** + * @brief 获取当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_work_frame(rm_robot_handle *handle, rm_frame_t *work_frame); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmState 机械臂状态查询 + * + * 机械臂当前状态、关节温度、电流、电压查询 + * @{ + */ +/** + * @brief 获取机械臂当前状态 + * + * @param handle 机械臂控制句柄 + * @param state 机械臂当前状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_arm_state(rm_robot_handle *handle,rm_current_arm_state_t *state); +/** + * @brief 获取关节当前温度 + * + * @param handle 机械臂控制句柄 + * @param temperature 关节1~7温度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_temperature(rm_robot_handle *handle, float *temperature); +/** + * @brief 获取关节当前电流 + * + * @param handle 机械臂控制句柄 + * @param current 关节1~7电流数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_current(rm_robot_handle *handle, float *current); +/** + * @brief 获取关节当前电压 + * + * @param handle 机械臂控制句柄 + * @param voltage 关节1~7电压数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_voltage(rm_robot_handle *handle, float *voltage); +/** + * @brief 获取当前关节角度 + * + * @param handle 机械臂控制句柄 + * @param joint 当前7个关节的角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_degree(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂所有状态信息 + * + * @param handle 机械臂控制句柄 + * @param state 存储机械臂信息的结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_all_state(rm_robot_handle *handle, rm_arm_all_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup InitPose 初始位置设置 + * + * 记录机械臂初始位置 + * @{ + */ +/** + * @brief 设置机械臂的初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_init_pose(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_init_pose(rm_robot_handle *handle, float *joint); +/** @} */ // 结束组的定义 + +/** + * @defgroup MovePlan 机械臂轨迹指令类 + * + * 关节运动、笛卡尔空间运动以及角度及位姿透传 + * @{ + */ +/** + * @brief 关节空间运动 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节1~7角度数组 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movej(rm_robot_handle *handle, const float *joint, int v, int r,int trajectory_connect,int block); +/** + * @brief 笛卡尔空间直线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movel(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间直线偏移运动 + * @details 该函数用于机械臂末端在当前位姿的基础上沿某坐标系(工具或工作)进行位移或旋转运动。 + * @param handle 机械臂控制句柄 + * @param offset 位置姿态偏移,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param frame_type 参考坐标系类型:0-工作,1-工具 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movel_offset(rm_robot_handle *handle,rm_pose_t offset, int v, int r, int trajectory_connect, int frame_type, int block); +/** + * @brief 样条曲线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @note 样条曲线运动需至少连续下发三个点位(trajectory_connect设置为1),否则运动轨迹为直线 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_moves(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间圆弧运动 + * + * @param handle 机械臂控制句柄 + * @param pose_via 中间点位姿,位置单位:米,姿态单位:弧度 + * @param pose_to 终点位姿 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @param r 交融半径百分比系数,0~100。 + * @param loop 规划圈数. + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movec(rm_robot_handle *handle,rm_pose_t pose_via, rm_pose_t pose_to, int v, int r, int loop, int trajectory_connect, int block); +/** + * @brief 该函数用于关节空间运动到目标位姿 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度。 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movej_p(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 角度不经规划,直接通过CANFD透传给机械臂 + * @details 角度透传到 CANFD,若指令正确,机械臂立即执行 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param config 角度透传模式配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_canfd(rm_robot_handle *handle, rm_movej_canfd_mode_t config); +/** + * @brief 位姿不经规划,直接通过CANFD透传给机械臂 + * @details 当目标位姿被透传到机械臂控制器时,控制器首先尝试进行逆解计算。 + * 若逆解成功且计算出的各关节角度与当前角度差异不大,则直接下发至关节执行,跳过额外的轨迹规划步骤。 + * 这一特性适用于需要周期性调整位姿的场景,如视觉伺服等应用。 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param config 姿态透传模式结构体 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_canfd(rm_robot_handle *handle, rm_movep_canfd_mode_t config); +/** + * @brief 关节空间跟随运动 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_follow(rm_robot_handle *handle,float *joint); +/** + * @brief 笛卡尔空间跟随运动 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_follow(rm_robot_handle *handle, rm_pose_t pose); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmMotionControl 机械臂运动控制指令类 + * + * 控制运动的急停、缓停、暂停、继续、清除轨迹以及查询当前规划类型 + * @{ + */ +/** + * @brief 轨迹缓停,在当前正在运行的轨迹上停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_slow_stop(rm_robot_handle *handle); +/** + * @brief 轨迹急停,关节最快速度停止,轨迹不可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_stop(rm_robot_handle *handle); +/** + * @brief 轨迹暂停,暂停在规划轨迹上,轨迹可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_pause(rm_robot_handle *handle); +/** + * @brief 轨迹暂停后,继续当前轨迹运动 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_continue(rm_robot_handle *handle); +/** + * @brief 清除当前轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_delete_current_trajectory(rm_robot_handle *handle); +/** + * @brief 清除所有轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_arm_delete_trajectory(rm_robot_handle *handle); +/** + * @brief 获取当前正在规划的轨迹信息 + * + * @param handle 机械臂控制句柄 + * @param type 返回的规划类型 + * @param data 无规划和关节空间规划为当前关节1~7角度数组;笛卡尔空间规划则为当前末端位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_current_trajectory(rm_robot_handle *handle,rm_arm_current_trajectory_e *type,float *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmTeachMove 机械臂示教指令类 + * + * 关节、位置、姿态的示教及步进控制 + * @{ + */ +/** + * @brief 关节步进 + * + * @param handle 机械臂控制句柄 + * @param joint_num 关节序号,1~7 + * @param step 步进的角度, + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_step(rm_robot_handle *handle,int joint_num, float step, int v, int block); +/** + * @brief 当前工作坐标系下,位置步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的距离,单位m,精确到0.001mm + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_step(rm_robot_handle *handle, rm_pos_teach_type_e type, float step, int v, int block); +/** + * @brief 当前工作坐标系下,姿态步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的弧度,单位rad,精确到0.001rad + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_step(rm_robot_handle *handle, rm_ort_teach_type_e type, float step, int v, int block); +/** + * @brief 切换示教运动坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_teach_frame(rm_robot_handle *handle, int frame_type); +/** + * @brief 获取示教参考坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_teach_frame(rm_robot_handle *handle,int *frame_type); +/** + * @brief 关节示教 + * + * @param handle 机械臂控制句柄 + * @param joint_num 示教关节的序号,1~7 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_teach(rm_robot_handle *handle,int joint_num, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间位置示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_teach(rm_robot_handle *handle,rm_pos_teach_type_e type, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间姿态示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_teach(rm_robot_handle *handle,rm_ort_teach_type_e type, int direction, int v); +/** + * @brief 示教停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_stop_teach(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerConfig 系统配置 + * + * 控制器状态获取、电源控制、错误清除、有线网口IP地址配置、软件信息获取 + * @{ + */ +/** + * @brief 获取控制器状态 + * + * @param handle 机械臂控制句柄 + * @param voltage 返回的电压 + * @param current 返回的电流 + * @param temperature 返回的温度 + * @param err_flag 控制器运行错误代码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_controller_state(rm_robot_handle *handle, float *voltage, float *current, float *temperature, int *err_flag); +/** + * @brief 设置机械臂电源 + * + * @param handle 机械臂控制句柄 + * @param arm_power 1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_power(rm_robot_handle *handle, int arm_power); +/** + * @brief 读取机械臂电源状态 + * + * @param handle 机械臂控制句柄 + * @param power_state 获取到的机械臂电源状态,1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_power_state(rm_robot_handle *handle, int *power_state); +/** + * @brief 读取控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @param day 读取到的时间 + * @param hour 读取到的时间 + * @param min 读取到的时间 + * @param sec 读取到的时间 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_system_runtime(rm_robot_handle *handle, int *day, int *hour, int *min, int *sec); +/** + * @brief 清零控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_runtime(rm_robot_handle *handle); +/** + * @brief 读取关节的累计转动角度 + * + * @param handle 机械臂控制句柄 + * @param joint_odom 各关节累计的转动角度,单位° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_odom(rm_robot_handle *handle, float *joint_odom); +/** + * @brief 清零关节累计转动的角度 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_joint_odom(rm_robot_handle *handle); +/** + * @brief 配置有线网口 IP 地址 + * + * @param handle 机械臂控制句柄 + * @param ip 有线网口 IP 地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_NetIP(rm_robot_handle *handle, const char* ip); +/** + * @brief 清除系统错误 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_err(rm_robot_handle *handle); +/** + * @brief 读取机械臂软件信息 + * + * @param handle 机械臂控制句柄 + * @param software_info 机械臂软件信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_software_info(rm_robot_handle *handle,rm_arm_software_version_t *software_info); +/** + * @brief 查询控制器RS485模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯,1-代表 modbus-RTU 主站模式,2-代表 modbus-RTU 从站模式; + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询工具端 RS485 模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯 1-代表 modbus-RTU 主站模式 + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询关节软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8 + * @param joint_v (四代控制器)获取到的各关节软件版本号字符串数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version, rm_version_t *joint_v); +/** + * @brief 查询末端接口板软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的末端接口板软件版本号,需转换为十六进制,例如获取到版本号393,转换为十六进制为189,则当前关节的版本号为 V1.8.9 + * @param tool_v (四代控制器)获取到的末端接口板软件版本号字符串 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version, rm_version_t *tool_v); +/** @} */ // 结束组的定义 + +/** + * @defgroup CommunicationConfig 配置通讯内容 + * + * 机械臂控制器可通过网口、WIFI、RS232-USB 接口和 RS485 接口与用户通信,用户使用时无需切换,可使用上述任一接口, + * 控制器收到指令后,若指令格式正确,则会通过相同的接口反馈数据。 + * @{ + */ +/** + * @brief 配置 wifiAP 模式 + * + * @param handle 机械臂控制句柄 + * @param wifi_name wifi名称 + * @param password wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFIAP 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_ap(rm_robot_handle *handle, const char* wifi_name, const char* password); +/** + * @brief 配置WiFi STA模式 + * + * @param handle 机械臂控制句柄 + * @param router_name 路由器名称 + * @param password 路由器Wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFISTA 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_sta(rm_robot_handle *handle, const char* router_name, const char* password); + +/** + * @brief 控制器RS485接口波特率设置,设置成功后蜂鸣器响 + * + * @param handle 机械臂控制句柄 + * @param baudrate 波特率:9600,19200,38400,115200和460800,若用户设置其他数据,控制器会默认按照460800处理。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 四代控制器不支持该接口 + * @attention 该指令下发后控制器会记录当前波特率,断电重启后仍会使用该波特率对外通信。 + */ +RM_INTERFACE_EXPORT int rm_set_RS485(rm_robot_handle *handle, int baudrate); +/** + * @brief 获取有线网卡信息,未连接有线网卡则会返回无效数据 + * + * @param handle 机械臂控制句柄 + * @param ip 网络地址 + * @param mask 子网掩码 + * @param mac MAC地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_wired_net(rm_robot_handle *handle, char * ip, char * mask, char * mac); +/** + * @brief 查询无线网卡网络信息 + * + * @param handle 机械臂控制句柄 + * @param wifi_net 无线网卡网络信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 结构体中的channel值只有在AP模式时才可获取到,标识 wifi 热点的物理信道号 + */ +RM_INTERFACE_EXPORT int rm_get_wifi_net(rm_robot_handle *handle, rm_wifi_net_t *wifi_net); +/** + * @brief 恢复网络出厂设置 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_net_default(rm_robot_handle *handle); +/** + * @brief 配置关闭 wifi 功能,需要重启后生效 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_close(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerIOConfig 控制器IO配置及获取 + * + * 机械臂控制器提供IO端口,用于与外部设备交互。数量和分类如下所示: + * + * @image html io.png + * @{ + */ +/** + * @brief 设置数字IO模式 + * + * @param handle 机械臂控制句柄 + * @param io_num 数字IO端口号,范围:1~4 + * @param config 数字IO配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_IO_mode(rm_robot_handle *handle, int io_num, rm_io_config_t config); +/** + * @brief 设置数字IO输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param config 数字IO配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_state(rm_robot_handle *handle, int io_num, rm_io_get_t* config); +/** + * @brief 获取所有 IO 输入状态 + * + * @param handle 机械臂控制句柄 + * @param DI_state 1~4端口数字输入状态数组,1:高,0:低,-1:该端口不是输入模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_input(rm_robot_handle *handle, int *DI_state); +/** + * @brief 获取所有 IO 输出状态 + * + * @param handle 机械臂控制句柄 + * @param DO_state 1~4端口数字输出状态数组,1:高,0:低,-1:该端口不是输出模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_output(rm_robot_handle *handle, int *DO_state); +/** + * @brief 设置控制器电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取控制器电源输出类 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup ToolIOConfig 末端工具 IO 控制 + * + * 机械臂末端工具端提供多种IO端口,用于与外部设备交互。数量和分类如下所示: + * @image html tool_io.png + * @{ + */ +/** + * @brief 设置工具端数字 IO 输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 设置工具端数字 IO 模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param io_mode 模式,0-输入状态,1-输出状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_IO_mode(rm_robot_handle *handle, int io_num, int io_mode); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param mode 0-输入模式,1-输出模式 + * @param state 0-低,1-高 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_IO_state(rm_robot_handle *handle, int* mode, int* state); +/** + * @brief 设置工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 电源输出设置为 5V 时,工具端的IO 暂不支持输入输出功能 + */ +RM_INTERFACE_EXPORT int rm_set_tool_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup GripperControl 末端工具—手爪控制 + * + * 睿尔曼机械臂末端配备了因时机器人公司的 EG2-4C2 手爪,为了便于用户操作手爪,机械臂控制器 + * 对用户开放了手爪的控制协议(手爪控制协议与末端modbus 功能互斥) + * @{ + */ +/** + * @brief 设置手爪行程,即手爪开口的最大值和最小值,设置成功后会自动保存,手爪断电不丢失 + * + * @param handle 机械臂控制句柄 + * @param min_limit 手爪开口最小值,范围:0~1000,无单位量纲 + * @param max_limit 手爪开口最大值,范围:0~1000,无单位量纲 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_route(rm_robot_handle *handle, int min_limit, int max_limit); +/** + * @brief 松开手爪,即手爪以指定的速度运动到开口最大处 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪松开速度,范围 1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_release(rm_robot_handle *handle, int speed, bool block, int timeout); +/** + * @brief 手爪力控夹取,手爪以设定的速度和力夹取,当夹持力超过设定的力阈值后,停止夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 手爪持续力控夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick_on(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 设置手爪达到指定位置 + * @details 手爪到达指定位置,当当前开口小于指定开口时,手爪以指定速度松开到指定开口位置;当当前开口大于指定开口时, + * 手爪以指定速度和力矩闭合往指定开口处闭合,当夹持力超过力矩阈值或者达到指定位置后,手爪停止。 + * @param handle 机械臂控制句柄 + * @param position 手爪开口位置,范围:1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_position(rm_robot_handle *handle, int position, bool block, int timeout); +/** + * @brief 查询夹爪状态 + * + * @param handle 机械臂控制句柄 + * @param state 夹爪状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 此接口默认不更新数据,从首次控制夹爪开始后,使能更新状态,如果此时控制灵巧手或打开末端modbus功能,将不再更新数据。另外夹爪需要支持最新的固件,方可支持此功能 + */ +RM_INTERFACE_EXPORT int rm_get_gripper_state(rm_robot_handle *handle, rm_gripper_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器六维力 + * + * 睿尔曼机械臂六维力版末端配备集成式六维力传感器,无需外部走线,用户可直接通过协议对六维力进行操作, + * 获取六维力数据。如下图所示,正上方为六维力的 Z 轴,航插反方向为六维力的 Y 轴,坐标系符合右手定则。 + * 机械臂位于零位姿态时,工具坐标系与六维力的坐标系方向一致。 + * 另外,六维力额定力 200N,额定力矩 8Nm,过载水平 300%FS,工作温度 5~80℃,准度 0.5%FS。使用过程中 + * 注意使用要求,防止损坏六维力传感器。 + * + * @image html force.png "六维力坐标系" + * @{ + */ +/** + * @brief 查询当前六维力传感器得到的力和力矩信息:Fx,Fy,Fz,Mx,My,Mz + * + * @param handle 机械臂控制句柄 + * @param data 力传感器数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。可能情况:当前机械臂不是六维力版本。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_force_data(rm_robot_handle *handle, rm_force_data_t *data); +/** + * @brief 将六维力数据清零,标定当前状态下的零位 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_force_data(rm_robot_handle *handle); +/** + * @brief 自动设置六维力重心参数 + * @details 设置六维力重心参数,六维力重新安装后,必须重新计算六维力所受到的初始力和重心。分别在不同姿态下,获取六维力的数据, + * 用于计算重心位置。该指令下发后,机械臂以固定的速度运动到各标定点。 + * 以RM65机械臂为例,四个标定点的关节角度分别为: + * 位置1关节角度:{0,0,-60,0,60,0} + * 位置2关节角度:{0,0,-60,0,-30,0} + * 位置3关节角度:{0,0,-60,0,-30,180} + * 位置4关节角度:{0,0,-60,0,-120,0} + * @attention 必须保证在机械臂静止状态下标定; + * 该过程不可中断,中断后必须重新标定。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_sensor(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定六维力数据 + * @details 六维力重新安装后,必须重新计算六维力所受到的初始力和重心。该手动标定流程,适用于空间狭窄工作区域,以防自动标定过程中 + * 机械臂发生碰撞,用户可以手动选取四个位置下发,当下发完四个点后,机械臂开始自动沿用户设置的目标运动,并在此过程中计算六维力重心。 + * @attention 上述4个位置必须按照顺序依次下发,当下发完位置4后,机械臂开始自动运行计算重心。 + * @param handle 机械臂控制句柄 + * @param count 点位;1~4 + * @param joint 关节角度,单位:° + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 计算成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_force(rm_robot_handle *handle, int count, float *joint, bool block); +/** + * @brief 停止标定力传感器重心 + * @details 在标定力传感器过程中,如果发生意外,发送该指令,停止机械臂运动,退出标定流程 + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_set_force_sensor(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup OneForceSensor 末端传感器一维力 + * + * 睿尔曼机械臂末端接口板集成了一维力传感器,可获取 Z 方向的力,量程200N,准度 0.5%FS。 + * @image html oneforce.png "一维力坐标系" + * @{ + */ +/** + * @brief 查询末端一维力数据 + * + * @param handle 机械臂控制句柄 + * @param data 一维力数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非力控版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_Fz(rm_robot_handle *handle, rm_fz_data_t *data); +/** + * @brief 清零末端一维力数据,清空一维力数据后,后续所有获取到的数据都是基于当前的偏置。 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_Fz(rm_robot_handle *handle); +/** + * @brief 自动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。 + * 分别在不同姿态下,获取一维力的数据,用于计算重心位置,该步骤对于基于一维力的力位混合控制操作具有重要意义。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_Fz(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。该手动标定流程, + * 适用于空间狭窄工作区域,以防自动标定过程中机械臂发生碰撞,用户可以手动选取2个位置下发,当下发完后, + * 机械臂开始自动沿用户设置的目标运动,并在此过程中计算一维力重心。 + * @param handle 机械臂控制句柄 + * @param joint1 位置1关节角度数组,单位:度 + * @param joint2 位置2关节角度数组,单位:度 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_Fz(rm_robot_handle *handle, float *joint1, float *joint2, bool block); +/** @} */ // 结束组的定义 + +/** + * @defgroup DragTeach 拖动示教 + * + * 睿尔曼机械臂在拖动示教过程中,可记录拖动的轨迹点,并根据用户的指令对轨迹进行复现。 + * @{ + */ +/** + * @brief 拖动示教开始 + * + * @param handle 机械臂控制句柄 + * @param trajectory_record 拖动示教时记录轨迹,0-不记录,1-记录轨迹 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_drag_teach(rm_robot_handle *handle, int trajectory_record); +/** + * @brief 拖动示教结束 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_teach(rm_robot_handle *handle); +/** + * @brief 开始复合模式拖动示教 + * @attention 仅支持三代控制器,四代控制器使用rm_start_multi_drag_teach_new + * @param handle 机械臂控制句柄 + * @param mode 拖动示教模式 0-电流环模式,1-使用末端六维力,只动位置,2-使用末端六维力,只动姿态,3-使用末端六维力,位置和姿态同时动 + * @param singular_wall 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, int mode, int singular_wall); +/** + * @brief 开始复合模式拖动示教-新参数 + * + * @param handle 机械臂控制句柄 + * @param teach_state 复合拖动示教参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach_new(rm_robot_handle *handle,rm_multi_drag_teach_t teach_state); +/** + * @brief 设置电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_drag_teach_sensitivity(rm_robot_handle *handle, int grade); +/** + * @brief 获取电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_drag_teach_sensitivity(rm_robot_handle *handle, int *grade); +/** + * @brief 运动到轨迹起点 + * @details 轨迹复现前,必须控制机械臂运动到轨迹起点,如果设置正确,机械臂将以20%的速度运动到轨迹起点 + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @see rm_run_drag_trajectory + */ +RM_INTERFACE_EXPORT int rm_drag_trajectory_origin(rm_robot_handle *handle, int block); +/** + * @brief 轨迹复现开始 + * + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误,请确保机械臂当前位置为拖动示教起点。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 必须在拖动示教结束后才能使用,同时保证机械臂位于拖动示教的起点位置,可调用rm_drag_trajectory_origin接口运动至起点位置 + * @see rm_drag_trajectory_origin + */ +RM_INTERFACE_EXPORT int rm_run_drag_trajectory(rm_robot_handle *handle, int block); +/** + * @brief 控制机械臂在轨迹复现过程中的暂停 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_pause_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中暂停之后的继续, + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_continue_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中的停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 保存拖动示教轨迹 + * + * @param handle 机械臂控制句柄 + * @param name 轨迹要保存的文件路径及名称,长度不超过300个字符,例: c:/rm_test.txt + * @param num 轨迹点数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,确保有拖动示教点位可保存。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件打开失败 + - -5: 文件名称截取失败 + - -6: 获取到的点位解析错误,保存失败 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory(rm_robot_handle *handle,const char* name, int *num); +/** + * @brief 力位混合控制 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param sensor 0-一维力;1-六维力 + * @param mode 0-基坐标系力控;1-工具坐标系力控; + * @param direction 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向 + * @param N 力的大小,单位N + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, int sensor, int mode, int direction, float N); +/** + * @brief 力位混合控制-新参数 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param param 力位混合控制参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position_new(rm_robot_handle *handle, rm_force_position_t param); + +/** + * @brief 结束力位混合控制 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position(rm_robot_handle *handle); +/** + * @brief 设置六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_set_force_drag_mode(rm_robot_handle *handle, int mode); +/** + * @brief 获取六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。处理建议:1、联系睿尔曼公司技术支持确认控制器版本是否支持此功能; + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_force_drag_mode(rm_robot_handle *handle, int *mode); +/** @} */ // 结束组的定义 + +/** + * @defgroup HandControl 五指灵巧手 + * + * 睿尔曼机械臂末端配置因时的五指灵巧手,可通过协议对灵巧手进行设置。 + * @{ + */ +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param posture_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_posture(rm_robot_handle *handle, int posture_num, bool block, int timeout); +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param seq_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_seq(rm_robot_handle *handle, int seq_num, bool block, int timeout); +/** + * @brief 设置灵巧手各自由度角度 + * @details 设置灵巧手角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,6个元素分别代表6个自由度的角度,范围:0~1000. 另外,-1代表该自由度不执行任何操作,保持当前状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_angle(rm_robot_handle *handle, const int *hand_angle); +/** + * @brief 设置灵巧手角度跟随控制 + * @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,最大表示范围为-32768到+32767,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-2000 + * @param block 设置0时为非阻塞模式;设置1时为阻塞模式,阻塞模式时超时20ms未返回认为接受失败。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_angle(rm_robot_handle *handle, const int *hand_angle, bool block); +/** + * @brief 灵巧手位置跟随控制 + * @details 设置灵巧手跟随位置,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_pos 手指位置数组,最大范围为0-65535,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-1000 + * @param block 设置0时为非阻塞模式;设置1时为阻塞模式,阻塞模式时超时20ms未返回认为接受失败。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_pos(rm_robot_handle *handle, const int *hand_pos, bool block); +/** + * @brief 设置灵巧手速度 + * + * @param handle 机械臂控制句柄 + * @param speed 手指速度,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 设置灵巧手力阈值 + * + * @param handle 机械臂控制句柄 + * @param hand_force 手指力,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_force(rm_robot_handle *handle, int hand_force); +/** @} */ // 结束组的定义 + +/** + * @defgroup ModbusConfig Modbus 配置 + * + * 睿尔曼机械臂在控制器和末端接口板上各提供一个RS485通讯接口,这些接口可通过接口配置为标准的Modbus RTU模式。 + * 在Modbus RTU模式下,用户可通过提供的接口对连接在端口上的外设进行读写操作。 + * + * @attention + * - 控制器的RS485接口在未配置为Modbus RTU模式时,可用于直接控制机械臂。 + * - Modbus RTU模式与机械臂控制模式不兼容。若需恢复机械臂控制模式,必须关闭该端口的Modbus RTU模式。 + * - 关闭Modbus RTU模式后,系统将自动切换回机械臂控制模式,使用波特率460800BPS,停止位1,数据位8,无校验。 + * + * 此外,I系列控制器还支持modbus-TCP主站配置,允许用户配置使用modbus-TCP主站,以连接外部设备的modbus-TCP从站。 + * + * @{ + */ +/** + * @brief 配置通讯端口ModbusRTU模式 + * @details 配置通讯端口ModbusRTU模式,机械臂启动后,要对通讯端口进行任何操作,必须先启动该指令,否则会返回报错信息。 + * 另外,机械臂会对用户的配置方式进行保存,机械臂重启后会自动恢复到用户断电之前配置的模式。 + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @param baudrate 波特率,支持 9600,115200,460800 三种常见波特率 + * @param timeout 超时时间,单位百毫秒。。对Modbus设备所有的读写指令,在规定的超时时间内未返回响应数据,则返回超时报错提醒。超时时间不能为0,若设置为0,则机械臂按1进行配置。 + * @note 其他配置默认为:数据位-8,停止位-1,奇偶校验-无 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbus_mode(rm_robot_handle *handle, int port, int baudrate, int timeout); +/** + * @brief 关闭通讯端口 Modbus RTU 模式 + * + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbus_mode(rm_robot_handle *handle, int port); +/** + * @brief 配置连接 ModbusTCP 从站 + * + * @attention 如需配置连接ModbusTCP从站,则该接口需要在创建机械臂句柄后调用一次,否则在读写寄存器时无法接收到返回值。 + * @param handle 机械臂控制句柄 + * @param ip 从机IP地址 + * @param port 端口号 + * @param timeout 超时时间,单位毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbustcp_mode(rm_robot_handle *handle, const char *ip, int port, int timeout); +/** + * @brief 配置关闭 ModbusTCP 从站 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbustcp_mode(rm_robot_handle *handle); +/** + * @brief 读线圈 + * + * @param handle 机械臂控制句柄 + * @param params 线圈读取参数结构体,该指令最多一次性支持读 8 个线圈数据,即返回的数据不会超过一个字节 + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读离散量输入 + * + * @param handle 机械臂控制句柄 + * @param params 离散量输入读取参数结构体,该指令最多一次性支持读 8 个离散量数据,即返回的数据不会超过一个字节 + * @param data 返回离散量,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_status(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读保持寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 保持寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 输入寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写单圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 单圈数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入线圈的数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_coil(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写单个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 单个寄存器数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入寄存器的数据,类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_register(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写多个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个寄存器数据写入参数结构体。其中寄存器每次写的数量不超过10个,即该结构体成员num<=10。 + * @param data 要写入寄存器的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据写入参数结构体。每次写的数量不超过 160 个,即该结构体成员num<=160。 + * @param data 要写入线圈的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据读取参数结构体,要读的线圈的数量 8< num <= 120,该指令最多一次性支持读 120 个线圈数据, 即 15 个 byte + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个保存寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个保存寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个输入寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup InstallPos 系统安装方式 + * + * 睿尔曼机械臂可支持不同形式的安装方式,但是安装方式不同,机器人的动力学模型参数和坐标系的方向也有所差别。 + * @{ + */ +/** + * @brief 设置安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角,单位 ° + * @param y 俯仰角,单位 ° + * @param z 方位角,单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_install_pose(rm_robot_handle *handle, float x, float y, float z); +/** + * @brief 获取安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角(out),单位 ° + * @param y 俯仰角(out),单位 ° + * @param z 方位角(out),单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_install_pose(rm_robot_handle *handle, float *x, float *y, float *z); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForcePositionControl 透传力位混合控制补偿 + * + * 针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将 + * 自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。 + * + * @attention 该功能只适用于一维力传感器和六维力传感器机械臂版本 + * + * 透传效果和周期、轨迹是否平滑有关,周期要求稳定,防止出现较大波动,用户使用该指令时请做好轨迹规划,轨迹规划的 + * 平滑程度决定了机械臂的运行状态。基础系列 WIFI 和网口模式透传周期最快 20ms,USB 和 RS485 模式透传周期最快 10ms。 + * 高速网口的透传周期最快也可到 10ms,不过在使用该高速网口前,需要使用指令打开配置。另外 I 系列有线网口周期最快可达 2ms。 + * + * @{ + */ +/** + * @brief 开启透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_force_position_move(rm_robot_handle *handle); +/** + * @brief 停止透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position_move(rm_robot_handle *handle); +/** + * @brief 透传力位混合补偿-角度方式 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节角度 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_joint(rm_robot_handle *handle,const float *joint,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-位姿方式 + * + * @param handle 机械臂控制句柄 + * @param pose 当前坐标系下目标位姿 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_pose(rm_robot_handle *handle, rm_pose_t pose,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-新参数 + * + * @param handle 机械臂控制句柄 + * @param param 透传力位混合补偿参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move(rm_robot_handle *handle, rm_force_position_move_t param); +/** @} */ // 结束组的定义 + +/** + * @defgroup LiftControl 升降机构 + * + * 升降机构速度开环控制、位置闭环控制及状态获取 + * @{ + */ +/** + * @brief 升降机构速度开环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:升降机构向下运动 + - speed>0:升降机构向上运动 + - speed=0:升降机构停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_speed(rm_robot_handle *handle, int speed); +/** + * @brief 升降机构位置闭环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param height 目标高度,单位 mm,范围:0~2600 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为升降机构。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_height(rm_robot_handle *handle, int speed, int height, int block); +/** + * @brief 获取升降机构状态 + * + * @param handle 机械臂控制句柄 + * @param state 当前升降机构状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_lift_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ExpandControl 通用扩展关节 + * + * 扩展关节速度环控制、位置环控制及状态获取 + * @{ + */ +/** + * @brief 扩展关节状态获取 + * + * @param handle 机械臂控制句柄 + * @param state 扩展关节状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_expand_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** + * @brief 扩展关节速度环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:扩展关节反方向运动 + - speed>0:扩展关节正方向运动 + - speed=0:扩展关节停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 扩展关节位置环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param pos 扩展关节角度,单位度 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为扩展关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_pos(rm_robot_handle *handle, int speed, int pos, int block); +/** @} */ // 结束组的定义 + +/** + * @defgroup OnlineProgramming 在线编程 + * + * 包含在线编程文件下发、在线编程文件管理、全局路点管理等相关功能接口。 + * @{ + */ +/** + * @brief 文件下发 + * + * @param handle 机械臂控制句柄 + * @param project 文件下发参数配置结构体 + * @param errline 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对,err_line 为 -1,则代表无错误 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件名称校验失败 + - -5: 文件读取失败 + - -6: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_send_project(rm_robot_handle *handle, rm_send_project_t project, int *errline); +/** + * @brief 轨迹规划中改变速度比例系数 + * + * @param handle 机械臂控制句柄 + * @param speed 当前进度条的速度数据 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_plan_speed(rm_robot_handle *handle, int speed); + +/** + * @brief 获取在线编程列表 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param trajectorys 在线编程程序列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_program_trajectory_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_program_trajectorys_t *trajectorys); + +/** + * @brief 开始运行指定编号轨迹 + * + * @param handle 机械臂控制句柄 + * @param id 运行指定的ID,1-100,存在轨迹可运行 + * @param speed 1-100,需要运行轨迹的速度,若设置为0,则按照存储的速度运行 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 运行状态已停止但未接收到运行成功,是否在外部停止了轨迹。 + */ +RM_INTERFACE_EXPORT int rm_set_program_id_run(rm_robot_handle *handle, int id, int speed, int block); +/** + * @brief 查询在线编程运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 在线编程运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_program_run_state(rm_robot_handle *handle, rm_program_run_state_t *run_state); +/** + * @brief 查询流程图运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 流程图运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_flowchart_program_run_state(rm_robot_handle *handle, rm_flowchart_run_state_t *run_state); +/** + * @brief 删除指定编号编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定编程轨迹的编号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_program_trajectory(rm_robot_handle *handle, int id); +/** + * @brief 修改指定编号的编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定在线编程轨迹编号 + * @param speed 更新后的规划速度比例 1-100 + * @param name 更新后的文件名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_program_trajectory(rm_robot_handle *handle, int id, int speed, const char* name); +/** + * @brief 设置 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id 设置 IO 默认运行的在线编程文件编号,支持 0-100,0 代表取消设置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_default_run_program(rm_robot_handle *handle, int id); +/** + * @brief 获取 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id IO 默认运行的在线编程文件编号,支持 0-100,0 代表无默认 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_default_run_program(rm_robot_handle *handle, int *id); +/** + * @brief 新增全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 新增全局路点参数(无需输入新增全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_add_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 更新全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 更新全局路点参数(无需输入更新全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 删除全局路点 + * + * @param handle 机械臂控制句柄 + * @param point_name 全局路点名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_global_waypoint(rm_robot_handle *handle, const char* point_name); +/** + * @brief 查询指定全局路点 + * + * @param handle 机械臂控制句柄 + * @param name 指定全局路点名称 + * @param point 返回指定的全局路点参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_global_waypoint(rm_robot_handle *handle, const char* name, rm_waypoint_t *point); +/** + * @brief 查询多个全局路点 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param point_list 返回的全局路点列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_global_waypoints_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_waypoint_list_t *point_list); +/** @} */ // 结束在线编程组的定义 + +/** + * @defgroup UdpConfig UDP主动上报 + * + * 睿尔曼机械臂提供 UDP 机械臂状态主动上报接口,使用时,需要和机械臂处于同一局域网络下,通过设置主动上报配置接口的目标 IP或和机械臂建立 TCP 连接, + * 机械臂即会主动周期性上报机械臂状态数据,数据周期可配置,默认 5ms。配置正确并开启三线程模式后,通过注册回调函数可接收并处理主动上报数据。 + * @{ + */ +/** + * @brief 设置 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config UDP配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_realtime_push_config_t config参数配置非法。 + */ +RM_INTERFACE_EXPORT int rm_set_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t config); +/** + * @brief 查询 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config 获取到的UDP机械臂状态主动上报配置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t *config); +/** @} */ // 结束组的定义 + +/** + * @defgroup Electronic_Fence 电子围栏和虚拟墙 + * + * I 系列机械臂具备电子围栏与虚拟墙功能,并提供了针对控制器所保存的电子围栏或虚拟墙几何模型参数的操作接口。 + * 用户可以通过这些接口,实现对电子围栏或虚拟墙的新增、查询、更新和删除操作,在使用中,可以灵活地使用保存在 + * 控制器中的参数配置,需要注意的是,目前控制器支持保存的参数要求不超过10 个。 + * + * 电子围栏 + * 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动 + * 轨迹可能超出电子围栏的界限时,系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。 + * @attention 电子围栏目前仅支持长方体和点面矢量平面这两种形状,并且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境。 + * + * 虚拟墙 + * 虚拟墙功能支持在电流环拖动示教与力控拖动示教两种模式下,对拖动范围进行精确限制。在这两种特定的示教模式下,用户可以借助虚拟墙功能,确保 + * 机械臂的拖动操作不会超出预设的范围。 + * @attention 虚拟墙功能目前支持长方体和球体两种形状,并仅在上述两种示教模式下有效。在其他操作模式下,此功能将自动失效。因此,请确保在正确的操作模式 + * 下使用虚拟墙功能,以充分发挥其限制拖动范围的作用。 + * + * @{ + */ +/** + * @brief 新增几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_add_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 更新几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_update_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 删除指定几何模型 + * + * @param handle 机械臂控制句柄 + * @param form_name 几何模型名称,不超过 10 个字节,支持字母、数字、下划线 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_electronic_fence_config(rm_robot_handle *handle, const char* form_name); +/** + * @brief 查询所有几何模型名称 + * + * @param handle 机械臂控制句柄 + * @param names 几何模型名称列表,长度为实际存在几何模型数量 + * @param len 几何模型名称列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_names(rm_robot_handle *handle, rm_fence_names_t *names, int *len); +/** + * @brief 查询指定几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param name 指定几何模型名称 + * @param config 返回几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_electronic_fence_config(rm_robot_handle *handle, const char* name, rm_fence_config_t *config); +/** + * @brief 查询所有几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config_list 几何模型信息列表,长度为实际存在几何模型数量 + * @param len 几何模型信息列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_infos(rm_robot_handle *handle, rm_fence_config_list_t *config_list, int *len); +/** + * @brief 设置电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动轨迹可能超出电子围栏的界限时, + * 系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。需要注意的是,电子围栏目前仅支持长方体和点面矢量平面这两种形状,并 + * 且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前电子围栏参数配置 + * + * @param handle 机械臂控制句柄 + * @param config 当前电子围栏参数结构体(无需设置电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前电子围栏参数 + * + * @param handle 机械臂控制句柄 + * @param config 返回当前电子围栏参数结构体(返回参数中不包含电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** + * @brief 设置虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(无需设置虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(返回参数中不包含虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** @} */ // 结束电子围栏组的定义 + +/** + * @defgroup SelfCollision 自碰撞安全检测 + * + * 睿尔曼机械臂支持自碰撞安全检测,自碰撞安全检测使能状态下,可确保在轨迹规划、示教等运动过程中机械臂的各个部分不会相互碰撞。 + * @attention 以上自碰撞安全检测功能目前只在仿真模式下生效,用于进行预演轨迹与轨迹优化。 + * @{ + */ +/** + * @brief 设置自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_self_collision_enable(rm_robot_handle *handle, bool state); +/** + * @brief 获取自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_self_collision_enable(rm_robot_handle *handle,bool *state); +/** @} */ // 结束组的定义 + + +/** + * @brief 设置末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_mode(rm_robot_handle *handle, int mode); + +/** + * @brief 查询末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_mode(rm_robot_handle *handle, int *mode); + +/** + * @brief 设置触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_touch(rm_robot_handle *handle, int mode); + +/** + * @brief 查询触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_rm_plus_touch(rm_robot_handle *handle, int *mode); + +/** + * @brief 读取末端设备基础信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备基础信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_base_info(rm_robot_handle *handle, rm_plus_base_info_t *info); + +/** + * @brief 读取末端设备实时信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备实时信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_state_info(rm_robot_handle *handle, rm_plus_state_info_t *info); + +/******************************************算法接口*******************************************************/ +/** + * @defgroup Algo 算法接口 + * + * 针对睿尔曼机械臂,提供正逆解、各种位姿参数转换等工具接口。 + * @{ + */ +/** + * @brief 查询算法库版本号 + * @return char* 返回版本号 + * @code + * char *version = rm_algo_version(); + * printf("algo version: %s\n", version); + * @endcode + */ +RM_INTERFACE_EXPORT char* rm_algo_version(void); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * + * @param Mode 机械臂型号 + * @param Type 传感器型号 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data(rm_robot_arm_model_e Mode, rm_force_type_e Type); +/** + * @brief 设置安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_angle(float x, float y, float z); +/** + * @brief 获取安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_get_angle(float* x, float* y, float* z); +/** + * @brief 设置工作坐标系 + * + * @param coord_work 坐标系数据(无需设置名称) + */ +RM_INTERFACE_EXPORT void rm_algo_set_workframe(const rm_frame_t* const coord_work); +/** + * @brief 获取当前工作坐标系 + * + * @param coord_work 当前工作坐标系(获取到的坐标系参数,不包括坐标系名称) + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_workframe(rm_frame_t* coord_work); +/** + * @brief 设置工具坐标系 + * + * @param coord_tool 坐标系数据(无需设置名称) + */ +RM_INTERFACE_EXPORT void rm_algo_set_toolframe(const rm_frame_t* const coord_tool); +/** + * @brief 获取算法当前工具坐标系 + * + * @param coord_tool 当前工具坐标系(获取到的坐标系参数,不包括坐标系名称) + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_toolframe(rm_frame_t* coord_tool); +/** + * @brief 设置算法关节最大限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_limit(const float* const joint_limit); +/** + * @brief 获取算法关节最大限位 + * + * @param joint_limit 返回关节最大限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_limit(float* joint_limit); +/** + * @brief 设置算法关节最小限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_min_limit(const float* const joint_limit); +/** + * @brief 获取算法关节最小限位 + * + * @param joint_limit 返回关节最小限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_min_limit(float* joint_limit); +/** + * @brief 设置算法关节最大速度 + * + * @param joint_slim_max RPM + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_speed(const float* const joint_slim_max); +/** + * @brief 获取算法关节最大速度 + * + * @param joint_slim_max 返回关节最大速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_speed(float* joint_slim_max); +/** + * @brief 设置算法关节最大加速度 + * + * @param joint_alim_max RPM/s + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_acc(const float* const joint_alim_max); +/** + * @brief 获取算法关节最大加速度 + * + * @param joint_alim_max 返回关节最大加速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_acc(float* joint_alim_max); +/** + * @brief 设置逆解求解模式 + * + * @param mode true:遍历模式,冗余参数遍历的求解策略。适于当前位姿跟要求解的位姿差别特别大的应用场景,如MOVJ_P、位姿编辑等,耗时较长 + false:单步模式,自动调整冗余参数的求解策略。适于当前位姿跟要求解的位姿差别特别小、连续周期控制的场景,如笛卡尔空间规划的位姿求解等,耗时短 + */ +RM_INTERFACE_EXPORT void rm_algo_set_redundant_parameter_traversal_mode(bool mode); +/** + * @brief 逆解函数,默认遍历模式,可使用Algo_Set_Redundant_Parameter_Traversal_Mode接口设置逆解求解模式 + * + * @param handle 机械臂控制句柄 + * @param params 逆解输入参数结构体 + * @param q_out 存放输出的关节角度数组 单位° + * @return int 逆解结果 + * - 0: 逆解成功 + * - 1: 逆解失败 + * - -1: 上一时刻关节角度输入为空或超关节限位 + * - -2: 目标位姿四元数不合法 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系、安装方式及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics(rm_robot_handle *handle, rm_inverse_kinematics_params_t params, float *q_out); + +/** + * @brief 计算逆运动学全解(当前仅支持六自由度机器人) + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param params 逆解输入参数结构体 + * @return rm_inverse_kinematics_all_solve_t 逆解的全解结构体 +*/ +RM_INTERFACE_EXPORT rm_inverse_kinematics_all_solve_t rm_algo_inverse_kinematics_all(rm_robot_handle *handle, rm_inverse_kinematics_params_t params); + +/** + * @brief 从多解中选取最优解(当前仅支持六自由度机器人) + * @param weight 权重,建议默认值为{1,1,1,1,1,1} + * @param params 待选解的全解结构体 + * @return int 最优解索引,选解结果为ik_solve.q_solve[i],如果没有合适的解返回-1(比如求出8组解,但是8组都有关节角度超限位,那么就返回-1) +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_select_ik_solve(float *weight, rm_inverse_kinematics_all_solve_t params); + + +/** + * @brief 检查逆解结果是否超出关节限位(当前仅支持六自由度机器人) + * @param q_solve 选解,单位:° + * @return int 0:未超限位,1~dof: 第i个关节超限位 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_position_limit(const float* const q_solve); + +/** + * @brief 检查逆解结果是否超速(当前仅支持六自由度机器人) + * @param dt 两帧数据之间的时间间隔,即控制周期,单位sec + * @param q_ref 参考关节角度或者第一帧数据角度,单位:° + * @param q_solve 求解结果,即下一帧要发送的角度 + * @return int 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_velocity_limit(float dt, const float* const q_ref, const float* const q_solve); + + +/** + * @brief 根据参考位形计算臂角大小(仅支持RM75) + * @param q_ref 当前参考位形的关节角度,单位° + * @param arm_angle 计算结果,当前参考位形对应的臂角大小,单位° + * @return int + * 0: 求解成功 + * -1: 求解失败,或机型非RM75 + * -2: q_ref 输入参数非法 + */ +RM_INTERFACE_EXPORT int rm_algo_calculate_arm_angle_from_config_rm75(float *q_ref, float *arm_angle); + +/** + * @brief 臂角法求解RM75逆运动学 + * @param params rm_inverse_kinematics_params_t,逆解参数结构体 + * @param arm_angle 指定轴角大小,单位:° + * @param q_solve 求解结果,单位:° + * @return int + * 0: 求解成功 + * -1: 求解失败 + * -2: 求解结果超出限位 + * -3: 机型非RM75 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics_rm75_for_arm_angle(rm_inverse_kinematics_params_t params, float arm_angle, float *q_solve); + +/** + * @brief 通过分析雅可比矩阵最小奇异值, 判断机器人是否处于奇异状态 + * @param q 要判断的关节角度(机械零位描述),单位:° + * @param 最小奇异值阈值,若传NULL,则使用内部默认值,默认值为0.01(该值在0-1之间) + * @return 0:在当前阈值条件下正常 + * -1:表示在当前阈值条件下判断为奇异区 + * -2:表示计算失败 + */ +RM_INTERFACE_EXPORT int rm_algo_universal_singularity_analyse(const float* const q, float singluar_value_limit); +/** + * @brief 设置自定义阈值(仅适用于解析法分析机器人奇异状态) + * @param limit_qe 肘部奇异区域范围设置(即J3接近0的范围),unit: °,default:about 10deg + * @param limit_qw 腕部奇异区域范围设置(即J5接近0的范围),unit: °,default:about 10deg + * @param limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_set_singularity_thresholds(float limit_qe_algo, float limit_qw_algo, float limit_d_algo); +/** + * @brief 获取自定义阈值(仅适用于解析法分析机器人奇异状态) + * + * @param limit_qe 肘部奇异区域范围获取(即J3接近0的范围), unit: °, default: about 10deg + * @param limit_qw 腕部奇异区域范围获取(即J5接近0的范围), unit: °, default: about 10deg + * @param limit_d 肩部奇异区域范围获取(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 + */ +RM_INTERFACE_EXPORT void rm_algo_kin_get_singularity_thresholds(float* limit_qe_algo, float* limit_qw_algo, float* limit_d_algo); + +/** + * @brief 恢复初始阈值(仅适用于解析法分析机器人奇异状态),阈值初始化为:limit_qe=10deg,limit_qw=10deg,limit_d = 0.05m +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_singularity_thresholds_init(); +/** + * @brief 解析法判断机器人是否处于奇异位形(仅支持六自由度) + * @param q 要判断的关节角度,单位:° + * @param distance 输出参数,返回腕部中心点到肩部奇异平面的距离,该值越接近0说明越接近肩部奇异,单位m,不需要时可传NULL + * @return 0表正常,-1表肩部奇异,-2表肘部奇异,-3表腕部奇异,-4表仅支持6自由度机械臂 +*/ +RM_INTERFACE_EXPORT int rm_algo_kin_robot_singularity_analyse(const float* const q, float *distance); +/** + * @brief 设置工具包络球参数 + * @param toolSphere_i 工具包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_set_tool_envelope(const int toolSphere_i, rm_tool_sphere_t data); + +/** + * @brief 获取工具包络球参数 + * @param toolSphere_i 工具rm_get_tool_voltage包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_get_tool_envelope(const int toolSphere_i, rm_tool_sphere_t *data); +/** + * @brief 自碰撞检测 + * @param joint 要判断的关节角度,单位:° + * @return int + * 0: 无碰撞 + * 1: 发生碰撞,超出关节限位将被认为发生碰撞 + */ +RM_INTERFACE_EXPORT int rm_algo_safety_robot_self_collision_detection(float *joint); +/** + * @brief 正解算法接口 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param joint 关节角度,单位:° + * + * @return rm_pose_t 目标位姿 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系、安装方式及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_forward_kinematics(rm_robot_handle *handle,const float* const joint); +/** + * @brief 欧拉角转四元数 + * + * @param eu 欧拉角,单位:rad + * @return rm_quat_t 四元数 + */ +RM_INTERFACE_EXPORT rm_quat_t rm_algo_euler2quaternion(rm_euler_t eu); +/** + * @brief 四元数转欧拉角 + * + * @param qua 四元数 + * @return rm_euler_t 欧拉角 + */ +RM_INTERFACE_EXPORT rm_euler_t rm_algo_quaternion2euler(rm_quat_t qua); +/** + * @brief 欧拉角转旋转矩阵 + * + * @param state 欧拉角,单位:rad + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_euler2matrix(rm_euler_t state); +/** + * @brief 位姿转旋转矩阵 + * + * @param state 位姿 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_pos2matrix(rm_pose_t state); +/** + * @brief 旋转矩阵转位姿 + * + * @param matrix 旋转矩阵 + * @return rm_pose_t 位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_matrix2pos(rm_matrix_t matrix); +/** + * @brief 基坐标系转工作坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在基坐标系下位姿 + * @return rm_pose_t 基坐标系在工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_base2workframe(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 工作坐标系转基坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在工作坐标系下位姿 + * @return rm_pose_t 工作坐标系在基坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_workframe2base(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 计算环绕运动位姿 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param curr_joint 当前关节角度 单位° + * @param rotate_axis 旋转轴: 1:x轴, 2:y轴, 3:z轴 + * @param rotate_angle 旋转角度: 旋转角度, 单位(度) + * @param choose_axis 指定计算时使用的坐标系 + * @return rm_pose_t 计算位姿结果 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_rotate_move(rm_robot_handle *handle,const float* const curr_joint, int rotate_axis, float rotate_angle, rm_pose_t choose_axis); +/** + * @brief 计算沿工具坐标系运动位姿 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param curr_joint 当前关节角度,单位:度 + * @param move_lengthx 沿X轴移动长度,单位:米 + * @param move_lengthy 沿Y轴移动长度,单位:米 + * @param move_lengthz 沿Z轴移动长度,单位:米 + * @return rm_pose_t 工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_cartesian_tool(rm_robot_handle *handle,const float* const curr_joint, float move_lengthx, + float move_lengthy, float move_lengthz); +/** + * @brief 计算Pos和Rot沿某坐标系有一定的位移和旋转角度后,所得到的位姿数据 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param poseCurrent 当前时刻位姿(欧拉角形式) + * @param deltaPosAndRot 移动及旋转数组,位置移动(单位:m),旋转(单位:度) + * @param frameMode 坐标系模式选择 0:Work(work即可任意设置坐标系),1:Tool + * @return rm_pose_t 平移旋转后的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_pose_move(rm_robot_handle *handle,rm_pose_t poseCurrent, const float *deltaPosAndRot, int frameMode); +/** + * @brief 末端位姿转成工具位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_end 基于世界坐标系和默认工具坐标系的末端位姿 + * @return rm_pose_t 基于工作坐标系和工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_end2tool(rm_robot_handle *handle,rm_pose_t eu_end); +/** + * @brief 工具位姿转末端位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_tool 基于工作坐标系和工具坐标系的末端位姿 + * @return rm_pose_t 基于世界坐标系和默认工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_tool2end(rm_robot_handle *handle,rm_pose_t eu_tool); +/** + * @brief 获取DH参数 + * + * @return rm_DH_t DH参数 + */ +RM_INTERFACE_EXPORT rm_dh_t rm_algo_get_dh(); +/** + * @brief 设置DH参数 + * + * @param dh DH参数 + */ +RM_INTERFACE_EXPORT void rm_algo_set_dh(rm_dh_t dh); + +/** @} */ // 结束算法组的定义 + +/*********************************************四代控制器新增接口*******************************************************/ + +/** + * @brief 查询轨迹列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list 轨迹列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_trajectory_file_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_trajectory_list_t *trajectory_list); +/** + * @brief 开始运行指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_run_trajectory(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 删除指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 保存轨迹到控制机器 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); + +/** + * @brief 设置机械臂急停状态 + * @param handle 机械臂控制句柄 + * @param state 急停状态,true:急停,false:恢复 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_arm_emergency_stop(rm_robot_handle *handle, bool state); +/** + * @brief 新增Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_add_modbus_tcp_master(rm_robot_handle *handle, rm_modbus_tcp_master_info_t master); +/** + * @brief 修改Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master 要修改的Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_update_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t master); +/** + * @brief 删除Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_modbus_tcp_master(rm_robot_handle *handle, const char *master_name); +/** + * @brief 查询Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t *master); +/** + * @brief 查询TCP主站列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list TCP主站列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_modbus_tcp_master_list_t *list); +/** + * @brief 设置控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_controller_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_rs485_mode_v4(rm_robot_handle *handle, int *controller_rs485_mode, int *baudrate); +/** + * @brief 设置工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_tool_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param tool_rs485_mode 0-代表modbus-RTU主站模式,1-代表灵巧手模式,2-代表夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_rs485_mode_v4(rm_robot_handle *handle, int *tool_rs485_mode, int *baudrate); +/** + * @brief Modbus RTU协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_status(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_holding_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_registers(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_status(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_holding_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_registers(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface_global.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface_global.h new file mode 100755 index 0000000..f771b85 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_interface_global.h @@ -0,0 +1,16 @@ +#ifndef RM_INTERFACE_GLOBAL_H +#define RM_INTERFACE_GLOBAL_H + +#ifdef __linux +#define RM_INTERFACE_EXPORT +#endif + +#if _WIN32 +#if defined(RM_INTERFACE_LIBRARY) +# define RM_INTERFACE_EXPORT __declspec(dllexport) +#else +# define RM_INTERFACE_EXPORT __declspec(dllexport) +#endif +#endif + +#endif // RM_INTERFACE_GLOBAL_H diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_service.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_service.h new file mode 100755 index 0000000..6050a3b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_service.h @@ -0,0 +1,4536 @@ +#ifndef RM_SERVICE_H +#define RM_SERVICE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "rm_interface.h" +#include "rm_interface_global.h" + +#ifdef __cplusplus +} + +class RM_Service { +public: +/** + * @defgroup Init_Class 初始化及连接 + * + * 此模块为API及机械臂初始化相关接口,包含API版本号查询、API初始化、连接/断开机械臂、日志设置、 + * 机械臂仿真/真实模式设置、机械臂信息获取、运动到位信息及机械臂实时状态信息回调函数注册等 + * @{ + */ +/** + * @brief 查询sdk版本号 + * + * @code + * char *version = rm_api_version(); + * printf("api version: %s\n", version); + * @endcode + * @return char* 返回版本号 + */ +RM_INTERFACE_EXPORT char* rm_api_version(void); +/** + * @brief 初始化线程模式 + * + * @param mode RM_SINGLE_MODE_E:单线程模式,单线程非阻塞等待数据返回; + * RM_DUAL_MODE_E:双线程模式,增加接收线程监测队列中的数据; + * RM_TRIPLE_MODE_E:三线程模式,在双线程模式基础上增加线程监测UDP接口数据; + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 创建线程失败。查看日志以获取具体错误 + * @see rm_create_robot_arm + */ +RM_INTERFACE_EXPORT int rm_init(rm_thread_mode_e mode); + +/** + * @brief 关闭所有连接,销毁所有线程 + * + * @return int 函数执行的状态码。 + - 0: 成功。 + */ +RM_INTERFACE_EXPORT int rm_destory(void); + +/** + * @brief 日志打印配置 + * + * @param LogCallback 日志打印回调函数 + * @param level 日志打印等级,0:debug级别,1:info级别,2:warn:级别,3:error级别 + */ + RM_INTERFACE_EXPORT void rm_set_log_call_back(void (*LogCallback)(const char* message, va_list args),int level); + +/** + * @brief 保存日志到文件 + * + * @param path 日志保存文件路径 + */ +RM_INTERFACE_EXPORT void rm_set_log_save(const char* path); + +/** + * @brief 设置全局超时时间 + * + * @param timeout 接收控制器返回指令超时时间,多数接口默认超时时间为500ms,单位ms + */ +RM_INTERFACE_EXPORT void rm_set_timeout(int timeout); + +/** + * @brief 创建一个机械臂,用于实现对该机械臂的控制 + * + * @param ip 机械臂的ip地址 + * @param port 机械臂的端口号 + * @return rm_robot_handle* 创建成功后,返回机械臂控制句柄,达到最大连接数5或者连接失败返回空 + * @see rm_init + */ +RM_INTERFACE_EXPORT rm_robot_handle *rm_create_robot_arm(const char *ip,int port); + +/** + * @brief 手动设置机械臂自由度 + * + * @param handle 机械臂控制句柄 + * @param dof 机械臂自由度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 设置失败,自由度设置不合理(负数或者大于10)。 + */ +RM_INTERFACE_EXPORT int rm_set_robot_dof(rm_robot_handle *handle, int dof); +/** + * @brief 根据句柄删除机械臂 + * + * @param handle 需要删除的机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + */ +RM_INTERFACE_EXPORT int rm_delete_robot_arm(rm_robot_handle *handle); +/** + * @brief 机械臂仿真/真实模式设置 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真 1:真实 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_run_mode(rm_robot_handle *handle, int mode); +/** + * @brief 机械臂仿真/真实模式获取 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真 1:真实 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_run_mode(rm_robot_handle *handle,int *mode); +/** + * @brief 获取机械臂基本信息 + * + * @param handle 机械臂控制句柄 + * @param robot_info 机械臂基本信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 获取到的机械臂基本信息非法,检查句柄是否已被删除。 + */ +RM_INTERFACE_EXPORT int rm_get_robot_info(rm_robot_handle *handle, rm_robot_info_t *robot_info); +/** + * @brief 机械臂事件回调注册 + * + * @param handle 机械臂控制句柄 + * @param event_callback 机械臂事件回调函数 + */ +RM_INTERFACE_EXPORT void rm_get_arm_event_call_back(rm_event_callback_ptr event_callback); +/** + * @brief UDP机械臂状态主动上报信息回调注册 + * + * @param handle 机械臂控制句柄 + * @param realtime_callback 机械臂状态信息回调函数 + */ +RM_INTERFACE_EXPORT void rm_realtime_arm_state_call_back(rm_realtime_arm_state_callback_ptr realtime_callback); +/** @} */ // 结束初始化组的定义 +/** + * @defgroup Joint_Config 关节配置 + * + * 对机械臂的关节参数进行设置,如果关节发生错误,则无法修改关节参数,必须先清除关节错误代码。另外设置关节之前, + * 必须先将关节掉使能,否则会设置不成功。 + * 关节所有参数在修改完成后,会自动保存到关节 Flash,立即生效,之后关节处于掉使能状态,修改完参数后必须 + * 发送指令控制关节上使能。 + * @attention 睿尔曼机械臂在出厂前所有参数都已经配置到最佳状态,一般不建议用户修改关节的底层参数。若用户确需修改,首先 + * 应使机械臂处于非使能状态,然后再发送修改参数指令,参数设置成功后,发送关节恢复使能指令。需要注意的是,关节恢复 + * 使能时,用户需要保证关节处于静止状态,以免上使能过程中关节发生报错。关节正常上使能后,用户方可控制关节运动。 + * @{ + */ +/** + * @brief 设置关节最大速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节最大速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节使能状态 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param en_state 1:上使能 0:掉使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_en_state(rm_robot_handle *handle,int joint_num,int en_state); +/** + * @brief 设置关节零位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_zero_pos(rm_robot_handle *handle,int joint_num); +/** + * @brief 清除关节错误代码 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_clear_err(rm_robot_handle *handle,int joint_num); +/** + * @brief 一键设置关节限位 + * + * @param handle 机械臂句柄 + * @param limit_mode 1-正式模式,各关节限位为规格参数中的软限位和硬件限位 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_joint_limit(rm_robot_handle *handle,int limit_mode); +/** + * @brief 查询关节最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节(驱动器)最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节(驱动器)最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节(驱动器)最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节(驱动器)最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节使能状态 + * + * @param handle 机械臂句柄 + * @param en_state 关节1~7使能状态数组,1-使能状态,0-掉使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_en_state(rm_robot_handle *handle,uint8_t *en_state); +/** + * @brief 查询关节错误代码 + * + * @param handle 机械臂句柄 + * @param err_flag 反馈关节错误代码,错误码请参见 \ref robotic_error + * @param brake_state 反馈关节抱闸状态,1 代表抱闸未打开,0 代表抱闸已打开 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_err_flag(rm_robot_handle *handle,uint16_t *err_flag,uint16_t *brake_state); +/** @} */ // 结束关节配置组的定义 + +/** + * @defgroup ArmTipVelocityParameters 机械臂末端参数配置 + * + * 机械臂末端运动参数设置及获取 + * @{ + */ +/** + * @brief 设置机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端参数为默认值 + * + * @param handle 机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_tcp_init(rm_robot_handle *handle); +/** + * @brief 设置机械臂动力学碰撞检测等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级:0~8,0-无碰撞,8-碰撞最灵敏 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_collision_state(rm_robot_handle *handle,int collision_stage); +/** + * @brief 查询碰撞防护等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级,范围:0~8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_collision_stage(rm_robot_handle *handle,int *collision_stage); +/** + * @brief 获取机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 获取机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 设置DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data(rm_robot_handle *handle, rm_dh_t dh); +/** + * @brief 获取DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_DH_data(rm_robot_handle *handle, rm_dh_t *dh); +/** + * @brief 恢复机械臂默认 DH 参数 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data_default(rm_robot_handle *handle); +/** @} */ // 结束组的定义 +/** + * @defgroup ToolCoordinateConfig 工具坐标系配置 + * + * 工具坐标系标定、切换、删除、修改、查询及工具包络参数等管理 + * @{ + */ +/** + * @brief 六点法自动设置工具坐标系 标记点位 + * + * @param handle 机械臂控制句柄 + * @param point_num 1~6代表6个标定点 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_tool_frame(rm_robot_handle *handle,int point_num); +/** + * @brief 六点法自动设置工具坐标系 提交 + * + * @param handle 机械臂控制句柄 + * @param name 工具坐标系名称,不能超过十个字节。 + * @param payload 新工具执行末端负载重量 单位kg + * @param x 新工具执行末端负载位置 位置x 单位m + * @param y 新工具执行末端负载位置 位置y 单位m + * @param z 新工具执行末端负载位置 位置z 单位m + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_generate_auto_tool_frame(rm_robot_handle *handle, const char *name,float payload,float x,float y,float z); +/** + * @brief 手动设置工具坐标系 + * + * @param handle 机械臂句柄 + * @param frame 新工具坐标系参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 切换当前工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 目标工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 删除指定工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 修改指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame 要修改的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_tool_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工具坐标系名称 + * @param frame 返回的工具参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_tool_frame(rm_robot_handle *handle, const char *name, rm_frame_t *frame); +/** + * @brief 获取当前工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param tool_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_tool_frame(rm_robot_handle *handle, rm_frame_t *tool_frame); +/** + * @brief 设置工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_envelope(rm_robot_handle *handle, rm_envelope_balls_list_t envelope); +/** + * @brief 获取工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param tool_name 控制器中已存在的工具坐标系名称 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回获取失败,检查工具坐标系是否存在。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_envelope(rm_robot_handle *handle, const char* tool_name, rm_envelope_balls_list_t *envelope); +/** @} */ // 结束组的定义 + +/** + * @defgroup WorkCoordinateConfig 工作坐标系配置 + * + * 工作坐标系标定、切换、删除、修改、查询等管理 + * @{ + */ +/** + * @brief 三点法自动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param workname 工作坐标系名称,不能超过十个字节。 + * @param point_num 1~3代表3个标定点,依次为原点、X轴一点、Y轴一点,4代表生成坐标系。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_work_frame(rm_robot_handle *handle,const char *workname, int point_num); +/** + * @brief 手动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 工作坐标系名称,不能超过十个字节。 + * @param pose 新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 切换当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 目标工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 删除指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 修改指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 指定工具坐标系名称 + * @param pose 更新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_work_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工作坐标系名称 + * @param pose 获取到的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_work_frame(rm_robot_handle *handle, const char *name, rm_pose_t *pose); +/** + * @brief 获取当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_work_frame(rm_robot_handle *handle, rm_frame_t *work_frame); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmState 机械臂状态查询 + * + * 机械臂当前状态、关节温度、电流、电压查询 + * @{ + */ +/** + * @brief 获取机械臂当前状态 + * + * @param handle 机械臂控制句柄 + * @param state 机械臂当前状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_arm_state(rm_robot_handle *handle,rm_current_arm_state_t *state); +/** + * @brief 获取关节当前温度 + * + * @param handle 机械臂控制句柄 + * @param temperature 关节1~7温度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_temperature(rm_robot_handle *handle, float *temperature); +/** + * @brief 获取关节当前电流 + * + * @param handle 机械臂控制句柄 + * @param current 关节1~7电流数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_current(rm_robot_handle *handle, float *current); +/** + * @brief 获取关节当前电压 + * + * @param handle 机械臂控制句柄 + * @param voltage 关节1~7电压数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_voltage(rm_robot_handle *handle, float *voltage); +/** + * @brief 获取当前关节角度 + * + * @param handle 机械臂控制句柄 + * @param joint 当前7个关节的角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_degree(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂所有状态信息 + * + * @param handle 机械臂控制句柄 + * @param state 存储机械臂信息的结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_all_state(rm_robot_handle *handle, rm_arm_all_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup InitPose 初始位置设置 + * + * 记录机械臂初始位置 + * @{ + */ +/** + * @brief 设置机械臂的初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_init_pose(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_init_pose(rm_robot_handle *handle, float *joint); +/** @} */ // 结束组的定义 + +/** + * @defgroup MovePlan 机械臂轨迹指令类 + * + * 关节运动、笛卡尔空间运动以及角度及位姿透传 + * @{ + */ +/** + * @brief 关节空间运动 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节1~7角度数组 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movej(rm_robot_handle *handle, const float *joint, int v, int r,int trajectory_connect,int block); +/** + * @brief 笛卡尔空间直线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movel(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间直线偏移运动 + * @details 该函数用于机械臂末端在当前位姿的基础上沿某坐标系(工具或工作)进行位移或旋转运动。 + * @param handle 机械臂控制句柄 + * @param offset 位置姿态偏移,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param frame_type 参考坐标系类型:0-工作,1-工具 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movel_offset(rm_robot_handle *handle,rm_pose_t offset, int v, int r, int trajectory_connect, int frame_type, int block); +/** + * @brief 样条曲线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @note 样条曲线运动需至少连续下发三个点位(trajectory_connect设置为1),否则运动轨迹为直线 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_moves(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间圆弧运动 + * + * @param handle 机械臂控制句柄 + * @param pose_via 中间点位姿,位置单位:米,姿态单位:弧度 + * @param pose_to 终点位姿 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param loop 规划圈数,目前默认0. + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movec(rm_robot_handle *handle,rm_pose_t pose_via, rm_pose_t pose_to, int v, int r, int loop, int trajectory_connect, int block); +/** + * @brief 该函数用于关节空间运动到目标位姿 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度。 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_movej_p(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 角度不经规划,直接通过CANFD透传给机械臂 + * @details 角度透传到 CANFD,若指令正确,机械臂立即执行 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @param follow true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + * @param expand 如果存在通用扩展轴,并需要进行透传,可使用该参数进行透传发送。 + * @param trajectory_mode 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + * @param radio 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~100,曲线拟合模式下取值范围0~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_canfd(rm_robot_handle *handle, float *joint, bool follow, int expand, int trajectory_mode=0, int radio=0); +/** + * @brief 位姿不经规划,直接通过CANFD透传给机械臂 + * @details 当目标位姿被透传到机械臂控制器时,控制器首先尝试进行逆解计算。 + * 若逆解成功且计算出的各关节角度与当前角度差异不大,则直接下发至关节执行,跳过额外的轨迹规划步骤。 + * 这一特性适用于需要周期性调整位姿的场景,如视觉伺服等应用。 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @param follow true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + * @param trajectory_mode 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + * @param radio 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~100,曲线拟合模式下取值范围0~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_canfd(rm_robot_handle *handle, rm_pose_t pose, bool follow, int trajectory_mode=0, int radio=0); +/** + * @brief 关节空间跟随运动 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_follow(rm_robot_handle *handle,float *joint); +/** + * @brief 笛卡尔空间跟随运动 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_follow(rm_robot_handle *handle, rm_pose_t pose); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmMotionControl 机械臂运动控制指令类 + * + * 控制运动的急停、缓停、暂停、继续、清除轨迹以及查询当前规划类型 + * @{ + */ +/** + * @brief 轨迹缓停,在当前正在运行的轨迹上停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_slow_stop(rm_robot_handle *handle); +/** + * @brief 轨迹急停,关节最快速度停止,轨迹不可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_stop(rm_robot_handle *handle); +/** + * @brief 轨迹暂停,暂停在规划轨迹上,轨迹可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_pause(rm_robot_handle *handle); +/** + * @brief 轨迹暂停后,继续当前轨迹运动 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_continue(rm_robot_handle *handle); +/** + * @brief 清除当前轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_delete_current_trajectory(rm_robot_handle *handle); +/** + * @brief 清除所有轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_arm_delete_trajectory(rm_robot_handle *handle); +/** + * @brief 获取当前正在规划的轨迹信息 + * + * @param handle 机械臂控制句柄 + * @param type 返回的规划类型 + * @param data 无规划和关节空间规划为当前关节1~7角度数组;笛卡尔空间规划则为当前末端位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_current_trajectory(rm_robot_handle *handle,rm_arm_current_trajectory_e *type,float *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmTeachMove 机械臂示教指令类 + * + * 关节、位置、姿态的示教及步进控制 + * @{ + */ +/** + * @brief 关节步进 + * + * @param handle 机械臂控制句柄 + * @param joint_num 关节序号,1~7 + * @param step 步进的角度, + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_step(rm_robot_handle *handle,int joint_num, float step, int v, int block); +/** + * @brief 当前工作坐标系下,位置步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的距离,单位m,精确到0.001mm + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_step(rm_robot_handle *handle, rm_pos_teach_type_e type, float step, int v, int block); +/** + * @brief 当前工作坐标系下,姿态步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的弧度,单位rad,精确到0.001rad + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_step(rm_robot_handle *handle, rm_ort_teach_type_e type, float step, int v, int block); +/** + * @brief 切换示教运动坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_teach_frame(rm_robot_handle *handle, int frame_type); +/** + * @brief 获取示教参考坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_teach_frame(rm_robot_handle *handle,int *frame_type); +/** + * @brief 关节示教 + * + * @param handle 机械臂控制句柄 + * @param joint_num 示教关节的序号,1~7 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_teach(rm_robot_handle *handle,int joint_num, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间位置示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_teach(rm_robot_handle *handle,rm_pos_teach_type_e type, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间姿态示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_teach(rm_robot_handle *handle,rm_ort_teach_type_e type, int direction, int v); +/** + * @brief 示教停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_stop_teach(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerConfig 系统配置 + * + * 控制器状态获取、电源控制、错误清除、有线网口IP地址配置、软件信息获取 + * @{ + */ +/** + * @brief 获取控制器状态 + * + * @param handle 机械臂控制句柄 + * @param voltage 返回的电压 + * @param current 返回的电流 + * @param temperature 返回的温度 + * @param err_flag 控制器运行错误代码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_controller_state(rm_robot_handle *handle, float *voltage, float *current, float *temperature, int *err_flag); +/** + * @brief 设置机械臂电源 + * + * @param handle 机械臂控制句柄 + * @param arm_power 1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_power(rm_robot_handle *handle, int arm_power); +/** + * @brief 读取机械臂电源状态 + * + * @param handle 机械臂控制句柄 + * @param power_state 获取到的机械臂电源状态,1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_power_state(rm_robot_handle *handle, int *power_state); +/** + * @brief 读取控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @param day 读取到的时间 + * @param hour 读取到的时间 + * @param min 读取到的时间 + * @param sec 读取到的时间 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_system_runtime(rm_robot_handle *handle, int *day, int *hour, int *min, int *sec); +/** + * @brief 清零控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_runtime(rm_robot_handle *handle); +/** + * @brief 读取关节的累计转动角度 + * + * @param handle 机械臂控制句柄 + * @param joint_odom 各关节累计的转动角度,单位° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_odom(rm_robot_handle *handle, float *joint_odom); +/** + * @brief 清零关节累计转动的角度 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_joint_odom(rm_robot_handle *handle); +/** + * @brief 配置有线网口 IP 地址 + * + * @param handle 机械臂控制句柄 + * @param ip 有线网口 IP 地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_NetIP(rm_robot_handle *handle, const char* ip); +/** + * @brief 清除系统错误 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_err(rm_robot_handle *handle); +/** + * @brief 读取机械臂软件信息 + * + * @param handle 机械臂控制句柄 + * @param software_info 机械臂软件信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_software_info(rm_robot_handle *handle,rm_arm_software_version_t *software_info); +/** + * @brief 查询控制器RS485模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯,1-代表 modbus-RTU 主站模式,2-代表 modbus-RTU 从站模式; + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持此接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询工具端 RS485 模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯 1-代表 modbus-RTU 主站模式 + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持此接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询关节软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version 获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8(三代控制器) + * @param joint_v 获取到的各关节软件版本号字符串数组(四代控制器) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version, rm_version_t *joint_v); +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version); +/** + * @brief 查询末端接口板软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的末端接口板软件版本号,需转换为十六进制,例如获取到版本号393,转换为十六进制为189,则当前关节的版本号为 V1.8.9 + * @param end_v (四代控制器)获取到的末端接口板软件版本号字符串 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version, rm_version_t *end_v); +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version); +/** @} */ // 结束组的定义 + +/** + * @defgroup CommunicationConfig 配置通讯内容 + * + * 机械臂控制器可通过网口、WIFI、RS232-USB 接口和 RS485 接口与用户通信,用户使用时无需切换,可使用上述任一接口, + * 控制器收到指令后,若指令格式正确,则会通过相同的接口反馈数据。 + * @{ + */ +/** + * @brief 配置 wifiAP 模式 + * + * @param handle 机械臂控制句柄 + * @param wifi_name wifi名称 + * @param password wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFIAP 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_ap(rm_robot_handle *handle, const char* wifi_name, const char* password); +/** + * @brief 配置WiFi STA模式 + * + * @param handle 机械臂控制句柄 + * @param router_name 路由器名称 + * @param password 路由器Wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFISTA 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_sta(rm_robot_handle *handle, const char* router_name, const char* password); + +/** + * @brief 控制器RS485接口波特率设置,设置成功后蜂鸣器响 + * + * @param handle 机械臂控制句柄 + * @param baudrate 波特率:9600,19200,38400,115200和460800,若用户设置其他数据,控制器会默认按照460800处理。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 四代控制器不支持该接口 + * @attention 该指令下发后控制器会记录当前波特率,断电重启后仍会使用该波特率对外通信。 + */ +RM_INTERFACE_EXPORT int rm_set_RS485(rm_robot_handle *handle, int baudrate); +/** + * @brief 获取有线网卡信息,未连接有线网卡则会返回无效数据 + * + * @param handle 机械臂控制句柄 + * @param ip 网络地址 + * @param mask 子网掩码 + * @param mac MAC地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_wired_net(rm_robot_handle *handle, char * ip, char * mask, char * mac); +/** + * @brief 查询无线网卡网络信息 + * + * @param handle 机械臂控制句柄 + * @param wifi_net 无线网卡网络信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 结构体中的channel值只有在AP模式时才可获取到,标识 wifi 热点的物理信道号 + */ +RM_INTERFACE_EXPORT int rm_get_wifi_net(rm_robot_handle *handle, rm_wifi_net_t *wifi_net); +/** + * @brief 恢复网络出厂设置 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_net_default(rm_robot_handle *handle); +/** + * @brief 配置关闭 wifi 功能,需要重启后生效 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_close(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerIOConfig 控制器IO配置及获取 + * + * 机械臂控制器提供IO端口,用于与外部设备交互。以下是具体的IO端口配置和特性: + * + * - 数字IO: + * - 数量: 4路 + * - 功能: DO/DI复用(数字输出/数字输入) + * - 电压范围: 可配置为0~24V + * @{ + */ +/** + * @brief 设置数字IO模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param io_mode 模式: + * 0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + * 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + * 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、 + * 12-输入初始位姿功能复用模式、13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * @param io_speed_mode 模式取值1或2(只有io_mode为14时生效): + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值。 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + * @param io_speed 速度取值范围0-100(只有io_mode为14时生效) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_IO_mode(rm_robot_handle *handle, int io_num, int io_mode, int io_speed_mode=0, int io_speed=0); +/** + * @brief 设置数字IO输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态 + * @param io_mode 模式: + * 0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + * 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + * 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、 + * 12-输入初始位姿功能复用模式13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * @param io_speed_mode 模式取值1或2(只有io_mode为14时生效): + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值。 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + * @param io_speed 速度取值范围0-100(只有io_mode为14时生效) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_state(rm_robot_handle *handle, int io_num, int* state, int* mode, int* io_speed_mode=nullptr, int* io_speed=nullptr); +/** + * @brief 获取所有 IO 输入状态 + * + * @param handle 机械臂控制句柄 + * @param DI_state 数字输入状态,1:高,0:低,-1:该端口不是输入模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_input(rm_robot_handle *handle, int *DI_state); +/** + * @brief 获取所有 IO 输出状态 + * + * @param handle 机械臂控制句柄 + * @param DO_state 数字输出状态,1:高,0:低,-1:该端口不是输出模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_output(rm_robot_handle *handle, int *DO_state); +/** + * @brief 设置控制器电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取控制器电源输出类 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup ToolIOConfig 末端工具 IO 控制 + * + * 机械臂末端工具端提供多种IO端口,用于与外部设备交互。以下是端口的具体配置和特性: + * - 电源输出: + * - 数量: 1路 + * - 可配置电压: 0V, 5V, 12V, 24V + * + * - 数字IO: + * - 数量: 2路 + * - 可配置性: 输入/输出均可配置 + * - 输入特性: + * - 参考电平: 12V~24V + * - 输出特性: + * - 电压范围: 5~24V(与输出电压一致) + * + * - 通讯接口: + * - 数量: 1路 + * - 可配置协议: RS485 + * @{ + */ +/** + * @brief 设置工具端数字 IO 输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 设置工具端数字 IO 模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param io_mode 模式,0-输入状态,1-输出状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_IO_mode(rm_robot_handle *handle, int io_num, int io_mode); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param state 0-输入模式,1-输出模式 + * @param mode 0-低,1-高 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_IO_state(rm_robot_handle *handle, int* state, int* mode); +/** + * @brief 设置工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 电源输出设置为 5V 时,工具端的IO 暂不支持输入输出功能 + */ +RM_INTERFACE_EXPORT int rm_set_tool_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup GripperControl 末端工具—手爪控制 + * + * 睿尔曼机械臂末端配备了因时机器人公司的 EG2-4C2 手爪,为了便于用户操作手爪,机械臂控制器 + * 对用户开放了手爪的控制协议(手爪控制协议与末端modbus 功能互斥) + * @{ + */ +/** + * @brief 设置手爪行程,即手爪开口的最大值和最小值,设置成功后会自动保存,手爪断电不丢失 + * + * @param handle 机械臂控制句柄 + * @param min_limit 手爪开口最小值,范围:0~1000,无单位量纲 + * @param max_limit 手爪开口最大值,范围:0~1000,无单位量纲 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_route(rm_robot_handle *handle, int min_limit, int max_limit); +/** + * @brief 松开手爪,即手爪以指定的速度运动到开口最大处 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪松开速度,范围 1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_release(rm_robot_handle *handle, int speed, bool block, int timeout); +/** + * @brief 手爪力控夹取,手爪以设定的速度和力夹取,当夹持力超过设定的力阈值后,停止夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick_on(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 设置手爪达到指定位置 + * @details 手爪到达指定位置,当当前开口小于指定开口时,手爪以指定速度松开到指定开口位置;当当前开口大于指定开口时, + * 手爪以指定速度和力矩闭合往指定开口处闭合,当夹持力超过力矩阈值或者达到指定位置后,手爪停止。 + * @param handle 机械臂控制句柄 + * @param position 手爪开口位置,范围:1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_position(rm_robot_handle *handle, int position, bool block, int timeout); +/** + * @brief 查询夹爪状态 + * + * @param handle 机械臂控制句柄 + * @param state 夹爪状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 此接口默认不更新数据,从首次控制夹爪开始后,使能更新状态,如果此时控制灵巧手或打开末端modbus功能,将不再更新数据。另外夹爪需要支持最新的固件,方可支持此功能 + */ +RM_INTERFACE_EXPORT int rm_get_gripper_state(rm_robot_handle *handle, rm_gripper_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器六维力 + * + * 睿尔曼机械臂六维力版末端配备集成式六维力传感器,无需外部走线,用户可直接通过协议对六维力进行操作, + * 获取六维力数据。如下图所示,正上方为六维力的 Z 轴,航插反方向为六维力的 Y 轴,坐标系符合右手定则。 + * 机械臂位于零位姿态时,工具坐标系与六维力的坐标系方向一致。 + * 另外,六维力额定力 200N,额定力矩 8Nm,过载水平 300%FS,工作温度 5~80℃,准度 0.5%FS。使用过程中 + * 注意使用要求,防止损坏六维力传感器。 + * @{ + */ +/** + * @brief 查询当前六维力传感器得到的力和力矩信息:Fx,Fy,Fz,Mx,My,Mz + * + * @param handle 机械臂控制句柄 + * @param data 力传感器数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_force_data(rm_robot_handle *handle, rm_force_data_t *data); +/** + * @brief 将六维力数据清零,标定当前状态下的零位 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_force_data(rm_robot_handle *handle); +/** + * @brief 自动设置六维力重心参数 + * @details 设置六维力重心参数,六维力重新安装后,必须重新计算六维力所受到的初始力和重心。分别在不同姿态下,获取六维力的数据, + * 用于计算重心位置。该指令下发后,机械臂以固定的速度运动到各标定点。 + * 以RM65机械臂为例,四个标定点的关节角度分别为: + * 位置1关节角度:{0,0,-60,0,60,0} + * 位置2关节角度:{0,0,-60,0,-30,0} + * 位置3关节角度:{0,0,-60,0,-30,180} + * 位置4关节角度:{0,0,-60,0,-120,0} + * @attention 必须保证在机械臂静止状态下标定; + * 该过程不可中断,中断后必须重新标定。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_sensor(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定六维力数据 + * @details 六维力重新安装后,必须重新计算六维力所受到的初始力和重心。该手动标定流程,适用于空间狭窄工作区域,以防自动标定过程中 + * 机械臂发生碰撞,用户可以手动选取四个位置下发,当下发完四个点后,机械臂开始自动沿用户设置的目标运动,并在此过程中计算六维力重心。 + * @attention 上述4个位置必须按照顺序依次下发,当下发完位置4后,机械臂开始自动运行计算重心。 + * @param handle 机械臂控制句柄 + * @param count 点位;1~4 + * @param joint 关节角度,单位:° + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 计算成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_force(rm_robot_handle *handle, int count, float *joint, bool block); +/** + * @brief 停止标定力传感器重心 + * @details 在标定力传感器过程中,如果发生意外,发送该指令,停止机械臂运动,退出标定流程 + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_set_force_sensor(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器一维力 + * + * 睿尔曼机械臂末端接口板集成了一维力传感器,可获取 Z 方向的力,量程200N,准度 0.5%FS。 + * @{ + */ +/** + * @brief 查询末端一维力数据 + * + * @param handle 机械臂控制句柄 + * @param data 一维力数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非力控版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_Fz(rm_robot_handle *handle, rm_fz_data_t *data); +/** + * @brief 清零末端一维力数据,清空一维力数据后,后续所有获取到的数据都是基于当前的偏置。 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_Fz(rm_robot_handle *handle); +/** + * @brief 自动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。 + * 分别在不同姿态下,获取一维力的数据,用于计算重心位置,该步骤对于基于一维力的力位混合控制操作具有重要意义。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_Fz(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。该手动标定流程, + * 适用于空间狭窄工作区域,以防自动标定过程中机械臂发生碰撞,用户可以手动选取2个位置下发,当下发完后, + * 机械臂开始自动沿用户设置的目标运动,并在此过程中计算一维力重心。 + * @param handle 机械臂控制句柄 + * @param joint1 位置1关节角度数组,单位:度 + * @param joint2 位置2关节角度数组,单位:度 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_Fz(rm_robot_handle *handle, float *joint1, float *joint2, bool block); +/** @} */ // 结束组的定义 + +/** + * @defgroup DragTeach 拖动示教 + * + * 睿尔曼机械臂在拖动示教过程中,可记录拖动的轨迹点,并根据用户的指令对轨迹进行复现。 + * @{ + */ +/** + * @brief 拖动示教开始 + * + * @param handle 机械臂控制句柄 + * @param trajectory_record 拖动示教时记录轨迹,0-不记录,1-记录轨迹 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_drag_teach(rm_robot_handle *handle, int trajectory_record); +/** + * @brief 拖动示教结束 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_teach(rm_robot_handle *handle); +/** + * @brief 开始复合模式拖动示教 + * @attention 仅支持三代控制器,四代控制器使用rm_start_multi_drag_teach_new + * @param handle 机械臂控制句柄 + * @param mode 拖动示教模式 0-电流环模式,1-使用末端六维力,只动位置,2-使用末端六维力,只动姿态,3-使用末端六维力,位置和姿态同时动 + * @param singular_wall 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, int mode, int singular_wall); +/** + * @brief 开始复合模式拖动示教-新参数 + * + * @param handle 机械臂控制句柄 + * @param teach_state 复合拖动示教参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, rm_multi_drag_teach_t teach_state); +/** + * @brief 设置电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_drag_teach_sensitivity(rm_robot_handle *handle, int grade); +/** + * @brief 获取电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_drag_teach_sensitivity(rm_robot_handle *handle, int *grade); +/** + * @brief 运动到轨迹起点 + * @details 轨迹复现前,必须控制机械臂运动到轨迹起点,如果设置正确,机械臂将以20%的速度运动到轨迹起点 + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @see rm_run_drag_trajectory + */ +RM_INTERFACE_EXPORT int rm_drag_trajectory_origin(rm_robot_handle *handle, int block); +/** + * @brief 轨迹复现开始 + * + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误,请确保机械臂当前位置为拖动示教起点。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 必须在拖动示教结束后才能使用,同时保证机械臂位于拖动示教的起点位置,可调用rm_drag_trajectory_origin接口运动至起点位置 + * @see rm_drag_trajectory_origin + */ +RM_INTERFACE_EXPORT int rm_run_drag_trajectory(rm_robot_handle *handle, int block); +/** + * @brief 控制机械臂在轨迹复现过程中的暂停 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_pause_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中暂停之后的继续, + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_continue_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中的停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 保存拖动示教轨迹 + * + * @param handle 机械臂控制句柄 + * @param name 轨迹要保存的文件路径及名称,长度不超过300个字符,例: c:/rm_test.txt + * @param num 轨迹点数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory(rm_robot_handle *handle, const char* name, int *num); +/** + * @brief 力位混合控制 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param sensor 0-一维力;1-六维力 + * @param mode 0-基坐标系力控;1-工具坐标系力控; + * @param direction 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向 + * @param N 力的大小,单位N + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, int sensor, int mode, int direction, float N); +/** + * @brief 力位混合控制-新参数 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param param 力位混合控制参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, rm_force_position_t param); +/** + * @brief 结束力位混合控制 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position(rm_robot_handle *handle); +/** + * @brief 设置六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_set_force_drag_mode(rm_robot_handle *handle, int mode); +/** + * @brief 获取六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。处理建议:1、联系睿尔曼公司技术支持确认控制器版本是否支持此功能; + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_force_drag_mode(rm_robot_handle *handle, int *mode); +/** @} */ // 结束组的定义 + +/** + * @defgroup HandControl 五指灵巧手 + * + * 睿尔曼机械臂末端配置因时的五指灵巧手,可通过协议对灵巧手进行设置。 + * @{ + */ +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param posture_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 超时未返回 + */ +RM_INTERFACE_EXPORT int rm_set_hand_posture(rm_robot_handle *handle, int posture_num, bool block, int timeout); +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param seq_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 超时未返回 + */ +RM_INTERFACE_EXPORT int rm_set_hand_seq(rm_robot_handle *handle, int seq_num, bool block, int timeout); +/** + * @brief 设置灵巧手各自由度角度 + * @details 设置灵巧手角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,范围:0~1000. 另外,-1代表该自由度不执行任何操作,保持当前状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_angle(rm_robot_handle *handle, const int *hand_angle); +/** + * @brief 设置灵巧手各自由度跟随角度 + * @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,最大表示范围为-32768到+32767,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-2000 + * @param block 设置等待机械臂返回状态超时时间,设置0时为非阻塞模式。单位为毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_angle(rm_robot_handle *handle, const int *hand_angle, int block); +/** + * @brief 灵巧手位置跟随控制 + * @details 设置灵巧手跟随位置,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_pos 手指位置数组,最大范围为0-65535,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-1000 + * @param block 设置等待机械臂返回状态超时时间,设置0时为非阻塞模式。单位为毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_pos(rm_robot_handle *handle, const int *hand_pos, int block); +/** + * @brief 设置灵巧手速度 + * + * @param handle 机械臂控制句柄 + * @param speed 手指速度,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 设置灵巧手力阈值 + * + * @param handle 机械臂控制句柄 + * @param hand_force 手指力,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_force(rm_robot_handle *handle, int hand_force); +/** @} */ // 结束组的定义 + +/** + * @defgroup ModbusConfig Modbus 配置 + * + * 睿尔曼机械臂在控制器和末端接口板上各提供一个RS485通讯接口,这些接口可通过JSON协议配置为标准的Modbus RTU模式。 + * 在Modbus RTU模式下,用户可通过JSON协议对连接在端口上的外设进行读写操作。 + * + * @attention + * - 控制器的RS485接口在未配置为Modbus RTU模式时,可用于直接控制机械臂。 + * - Modbus RTU模式与机械臂控制模式不兼容。若需恢复机械臂控制模式,必须关闭该端口的Modbus RTU模式。 + * - 关闭Modbus RTU模式后,系统将自动切换回机械臂控制模式,使用波特率460800BPS,停止位1,数据位8,无校验。 + * + * 此外,I系列控制器还支持modbus-TCP主站配置,允许用户配置使用modbus-TCP主站,以连接外部设备的modbus-TCP从站。 + * + * @{ + */ +/** + * @brief 配置通讯端口ModbusRTU模式 + * @details 配置通讯端口ModbusRTU模式,机械臂启动后,要对通讯端口进行任何操作,必须先启动该指令,否则会返回报错信息。 + * 另外,机械臂会对用户的配置方式进行保存,机械臂重启后会自动恢复到用户断电之前配置的模式。 + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @param baudrate 波特率,支持 9600,115200,460800 三种常见波特率 + * @param timeout 超时时间,单位百毫秒。。对Modbus设备所有的读写指令,在规定的超时时间内未返回响应数据,则返回超时报错提醒。超时时间不能为0,若设置为0,则机械臂按1进行配置。 + * @note 其他配置默认为:数据位-8,停止位-1,奇偶校验-无 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbus_mode(rm_robot_handle *handle, int port, int baudrate, int timeout); +/** + * @brief 关闭通讯端口 Modbus RTU 模式 + * + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbus_mode(rm_robot_handle *handle, int port); +/** + * @brief 配置连接 ModbusTCP 从站 + * + * @param handle 机械臂控制句柄 + * @param ip 从机IP地址 + * @param port 端口号 + * @param timeout 超时时间,单位毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbustcp_mode(rm_robot_handle *handle, const char *ip, int port, int timeout); +/** + * @brief 关闭通讯端口ModbusRTU模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbustcp_mode(rm_robot_handle *handle); +/** + * @brief 读线圈 + * + * @param handle 机械臂控制句柄 + * @param params 线圈读取参数结构体,该指令最多一次性支持读 8 个线圈数据,即返回的数据不会超过一个字节 + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读离散量输入 + * + * @param handle 机械臂控制句柄 + * @param params 离散量输入读取参数结构体,该指令最多一次性支持读 8 个离散量数据,即返回的数据不会超过一个字节 + * @param data 返回离散量,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_status(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读保持寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 保持寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 输入寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写单圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 单圈数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入线圈的数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_coil(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写单个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 单个寄存器数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入寄存器的数据,类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_register(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写多个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个寄存器数据写入参数结构体。其中寄存器每次写的数量不超过10个,即该结构体成员num<=10。 + * @param data 要写入寄存器的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据写入参数结构体。每次写的数量不超过 160 个,即该结构体成员num<=160。 + * @param data 要写入线圈的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据读取参数结构体,要读的线圈的数量 8< num <= 120,该指令最多一次性支持读 120 个线圈数据, 即 15 个 byte + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个保存寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个保存寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个输入寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup InstallPos 系统安装方式 + * + * 睿尔曼机械臂可支持不同形式的安装方式,但是安装方式不同,机器人的动力学模型参数和坐标系的方向也有所差别。 + * @{ + */ +/** + * @brief 设置安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角,单位 ° + * @param y 俯仰角,单位 ° + * @param z 方位角,单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_install_pose(rm_robot_handle *handle, float x, float y, float z); +/** + * @brief 获取安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角(out),单位 ° + * @param y 俯仰角(out),单位 ° + * @param z 方位角(out),单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_install_pose(rm_robot_handle *handle, float *x, float *y, float *z); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForcePositionControl 透传力位混合控制补偿 + * + * 针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将 + * 自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。 + * + * @attention 该功能只适用于一维力传感器和六维力传感器机械臂版本 + * + * 透传效果和周期、轨迹是否平滑有关,周期要求稳定,防止出现较大波动,用户使用该指令时请做好轨迹规划,轨迹规划的 + * 平滑程度决定了机械臂的运行状态。基础系列 WIFI 和网口模式透传周期最快 20ms,USB 和 RS485 模式透传周期最快 10ms。 + * 高速网口的透传周期最快也可到 10ms,不过在使用该高速网口前,需要使用指令打开配置。另外 I 系列有线网口周期最快可达 2ms。 + * @{ + */ +/** + * @brief 开启透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_force_position_move(rm_robot_handle *handle); +/** + * @brief 停止透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position_move(rm_robot_handle *handle); +/** + * @brief 透传力位混合补偿-角度方式 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节角度 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_joint(rm_robot_handle *handle,const float *joint,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-位姿方式 + * + * @param handle 机械臂控制句柄 + * @param pose 当前坐标系下目标位姿 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_pose(rm_robot_handle *handle, rm_pose_t pose,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-新参数 + * + * @param handle 机械臂控制句柄 + * @param param 透传力位混合补偿参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move(rm_robot_handle *handle, rm_force_position_move_t param); +/** @} */ // 结束组的定义 + +/** + * @defgroup LiftControl 升降机构 + * + * 升降机构速度开环控制、位置闭环控制及状态获取 + * @{ + */ +/** + * @brief 升降机构速度开环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:升降机构向下运动 + - speed>0:升降机构向上运动 + - speed=0:升降机构停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_speed(rm_robot_handle *handle, int speed); +/** + * @brief 升降机构位置闭环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param height 目标高度,单位 mm,范围:0~2600 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为升降机构。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_height(rm_robot_handle *handle, int speed, int height, int block); +/** + * @brief 获取升降机构状态 + * + * @param handle 机械臂控制句柄 + * @param state 当前升降机构状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_lift_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ExpandControl 通用扩展关节 + * + * 扩展关节速度环控制、位置环控制及状态获取 + * @{ + */ +/** + * @brief 扩展关节状态获取 + * + * @param handle 机械臂控制句柄 + * @param state 扩展关节状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_expand_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** + * @brief 扩展关节速度环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:扩展关节反方向运动 + - speed>0:扩展关节正方向运动 + - speed=0:扩展关节停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 扩展关节位置环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param pos 扩展关节角度,单位度 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为扩展关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_pos(rm_robot_handle *handle, int speed, int pos, int block); +/** @} */ // 结束组的定义 + +/** + * @defgroup OnlineProgramming 在线编程 + * + * 包含在线编程文件下发、在线编程文件管理、全局路点管理等相关功能接口。 + * @{ + */ +/** + * @brief 文件下发 + * + * @param handle 机械臂控制句柄 + * @param project 文件下发参数配置结构体 + * @param errline 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件名称校验失败 + - -5: 文件读取失败 + - -6: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_send_project(rm_robot_handle *handle, rm_send_project_t project, int *errline); +/** + * @brief 轨迹规划中改变速度比例系数 + * + * @param handle 机械臂控制句柄 + * @param speed 当前进度条的速度数据 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_plan_speed(rm_robot_handle *handle, int speed); + +/** + * @brief 获取在线编程列表 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param trajectorys 在线编程程序列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_program_trajectory_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_program_trajectorys_t *trajectorys); + +/** + * @brief 开始运行指定编号轨迹 + * + * @param handle 机械臂控制句柄 + * @param id 运行指定的ID,1-100,存在轨迹可运行 + * @param speed 1-100,需要运行轨迹的速度,若设置为0,则按照存储的速度运行 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 运行状态已停止但未接收到运行成功,是否在外部停止了轨迹。 + */ +RM_INTERFACE_EXPORT int rm_set_program_id_run(rm_robot_handle *handle, int id, int speed, int block); +/** + * @brief 查询在线编程运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 在线编程运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_program_run_state(rm_robot_handle *handle, rm_program_run_state_t *run_state); +/** + * @brief 查询流程图运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 流程图运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_flowchart_program_run_state(rm_robot_handle *handle, rm_flowchart_run_state_t *run_state); +/** + * @brief 删除指定编号编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定编程轨迹的编号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_program_trajectory(rm_robot_handle *handle, int id); +/** + * @brief 修改指定编号的编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定在线编程轨迹编号 + * @param speed 更新后的规划速度比例 1-100 + * @param name 更新后的文件名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_program_trajectory(rm_robot_handle *handle, int id, int speed, const char* name); +/** + * @brief 设置 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id 设置 IO 默认运行的在线编程文件编号,支持 0-100,0 代表取消设置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_default_run_program(rm_robot_handle *handle, int id); +/** + * @brief 获取 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id IO 默认运行的在线编程文件编号,支持 0-100,0 代表无默认 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_default_run_program(rm_robot_handle *handle, int *id); +/** + * @brief 新增全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 新增全局路点参数(无需输入新增全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_add_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 更新全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 更新全局路点参数(无需输入更新全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 删除全局路点 + * + * @param handle 机械臂控制句柄 + * @param point_name 全局路点名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_global_waypoint(rm_robot_handle *handle, const char* point_name); +/** + * @brief 查询指定全局路点 + * + * @param handle 机械臂控制句柄 + * @param name 指定全局路点名称 + * @param point 返回指定的全局路点参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_global_waypoint(rm_robot_handle *handle, const char* name, rm_waypoint_t *point); +/** + * @brief 查询多个全局路点 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param point_list 返回的全局路点列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_global_waypoints_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_waypoint_list_t *point_list); +/** @} */ // 结束在线编程组的定义 + +/** + * @defgroup UdpConfig UDP主动上报 + * + * 睿尔曼机械臂提供 UDP 机械臂状态主动上报接口,使用时,需要和机械臂处于同一局域网络下,通过设置主动上报配置接口的目标 IP或和机械臂建立 TCP 连接, + * 机械臂即会主动周期性上报机械臂状态数据,数据周期可配置,默认 5ms。配置正确并开启三线程模式后,通过注册回调函数可接收并处理主动上报数据。 + * @{ + */ +/** + * @brief 设置 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config UDP配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t config); +/** + * @brief 查询 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config 获取到的UDP机械臂状态主动上报配置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t *config); +/** @} */ // 结束组的定义 + +/** + * @defgroup Electronic_Fence 电子围栏和虚拟墙 + * + * I 系列机械臂具备电子围栏与虚拟墙功能,并提供了针对控制器所保存的电子围栏或虚拟墙几何模型参数的操作接口。 + * 用户可以通过这些接口,实现对电子围栏或虚拟墙的新增、查询、更新和删除操作,在使用中,可以灵活地使用保存在 + * 控制器中的参数配置,需要注意的是,目前控制器支持保存的参数要求不超过10 个。 + * + * 电子围栏 + * 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动 + * 轨迹可能超出电子围栏的界限时,系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。 + * @attention 电子围栏目前仅支持长方体和点面矢量平面这两种形状,并且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境。 + * + * 虚拟墙 + * 虚拟墙功能支持在电流环拖动示教与力控拖动示教两种模式下,对拖动范围进行精确限制。在这两种特定的示教模式下,用户可以借助虚拟墙功能,确保 + * 机械臂的拖动操作不会超出预设的范围。 + * @attention 虚拟墙功能目前支持长方体和球体两种形状,并仅在上述两种示教模式下有效。在其他操作模式下,此功能将自动失效。因此,请确保在正确的操作模式 + * 下使用虚拟墙功能,以充分发挥其限制拖动范围的作用。 + * + * @{ + */ +/** + * @brief 新增几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 -4:form设置有误 + */ +RM_INTERFACE_EXPORT int rm_add_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 更新几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 删除指定几何模型 + * + * @param handle 机械臂控制句柄 + * @param form_name 几何模型名称,不超过 10 个字节,支持字母、数字、下划线 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_electronic_fence_config(rm_robot_handle *handle, const char* form_name); +/** + * @brief 查询所有几何模型名称 + * + * @param handle 机械臂控制句柄 + * @param names 几何模型名称列表,长度为实际存在几何模型数量 + * @param len 几何模型名称列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_names(rm_robot_handle *handle, rm_fence_names_t *names, int *len); +/** + * @brief 查询指定几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param name 指定几何模型名称 + * @param config 返回几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_electronic_fence_config(rm_robot_handle *handle, const char* name, rm_fence_config_t *config); +/** + * @brief 查询所有几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config_list 几何模型信息列表,长度为实际存在几何模型数量 + * @param len 几何模型信息列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_infos(rm_robot_handle *handle, rm_fence_config_list_t *config_list, int *len); +/** + * @brief 设置电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动轨迹可能超出电子围栏的界限时, + * 系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。需要注意的是,电子围栏目前仅支持长方体和点面矢量平面这两种形状,并 + * 且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前电子围栏参数配置 + * + * @param handle 机械臂控制句柄 + * @param config 当前电子围栏参数结构体(无需设置电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前电子围栏参数 + * + * @param handle 机械臂控制句柄 + * @param config 返回当前电子围栏参数结构体(返回参数中不包含电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** + * @brief 设置虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(无需设置虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(返回参数中不包含虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** @} */ // 结束电子围栏组的定义 + +/** + * @defgroup SelfCollision 自碰撞安全检测 + * + * 睿尔曼机械臂支持自碰撞安全检测,自碰撞安全检测使能状态下,可确保在轨迹规划、示教等运动过程中机械臂的各个部分不会相互碰撞。 + * @attention 以上自碰撞安全检测功能目前只在仿真模式下生效,用于进行预演轨迹与轨迹优化。 + * @{ + */ +/** + * @brief 设置自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_self_collision_enable(rm_robot_handle *handle, bool state); +/** + * @brief 获取自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_self_collision_enable(rm_robot_handle *handle,bool *state); +/** @} */ // 结束组的定义 + +/** + * @brief 设置末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_mode(rm_robot_handle *handle, int mode); + +/** + * @brief 查询末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_mode(rm_robot_handle *handle, int *mode); + +/** + * @brief 设置触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_touch(rm_robot_handle *handle, int mode); + +/** + * @brief 查询触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_touch(rm_robot_handle *handle, int *mode); + +/** + * @brief 读取末端设备基础信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备基础信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_base_info(rm_robot_handle *handle, rm_plus_base_info_t *info); + +/** + * @brief 读取末端设备实时信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备实时信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_state_info(rm_robot_handle *handle, rm_plus_state_info_t *info); + + + +/******************************************算法接口*******************************************************/ +/** + * @defgroup Algo 算法接口 + * + * 针对睿尔曼机械臂,提供正逆解、各种位姿参数转换等工具接口。 + * @{ + */ +/** + * @brief 查询算法库版本号 + * @return char* 返回版本号 + */ +RM_INTERFACE_EXPORT char* rm_algo_version(void); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * + * @param Mode 机械臂型号 + * @param Type 传感器型号 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data(rm_robot_arm_model_e Mode, rm_force_type_e Type); +/** + * @brief 设置安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_angle(float x, float y, float z); +/** + * @brief 获取安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_get_angle(float* x, float* y, float* z); +/** + * @brief 设置工作坐标系 + * + * @param coord_work 坐标系数据 + */ +RM_INTERFACE_EXPORT void rm_algo_set_workframe(const rm_frame_t* const coord_work); +/** + * @brief 获取当前工作坐标系 + * + * @param coord_work 当前工作坐标系 + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_workframe(rm_frame_t* coord_work); +/** + * @brief 设置工具坐标系 + * + * @param coord_tool 坐标系数据 + */ +RM_INTERFACE_EXPORT void rm_algo_set_toolframe(const rm_frame_t* const coord_tool); +/** + * @brief 获取当前工具坐标系 + * + * @param coord_tool 当前工具坐标系 + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_toolframe(rm_frame_t* coord_tool); +/** + * @brief 设置关节最大限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_limit(const float* const joint_limit); +/** + * @brief 获取关节最大限位 + * + * @param joint_limit 返回关节最大限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_limit(float* joint_limit); +/** + * @brief 设置关节最小限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_min_limit(const float* const joint_limit); +/** + * @brief 获取关节最小限位 + * + * @param joint_limit 返回关节最小限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_min_limit(float* joint_limit); +/** + * @brief 设置关节最大速度 + * + * @param joint_slim_max RPM + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_speed(const float* const joint_slim_max); +/** + * @brief 获取关节最大速度 + * + * @param joint_slim_max 返回关节最大速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_speed(float* joint_slim_max); +/** + * @brief 设置关节最大加速度 + * + * @param joint_alim_max RPM/s + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_acc(const float* const joint_alim_max); +/** + * @brief 获取关节最大加速度 + * + * @param joint_alim_max 返回关节最大加速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_acc(float* joint_alim_max); +/** + * @brief 设置逆解求解模式 + * + * @param mode true:遍历模式,冗余参数遍历的求解策略。适于当前位姿跟要求解的位姿差别特别大的应用场景,如MOVJ_P、位姿编辑等,耗时较长 + false:单步模式,自动调整冗余参数的求解策略。适于当前位姿跟要求解的位姿差别特别小、连续周期控制的场景,如笛卡尔空间规划的位姿求解等,耗时短 + */ +RM_INTERFACE_EXPORT void rm_algo_set_redundant_parameter_traversal_mode(bool mode); +/** + * @brief 逆解函数,默认遍历模式,可使用Algo_Set_Redundant_Parameter_Traversal_Mode接口设置逆解求解模式 + * + * @param handle 机械臂控制句柄 + * @param params 逆解输入参数结构体 + * @param q_out 输出的关节角度 单位° + * @return int 逆解结果 + * - 0: 逆解成功 + * - 1: 逆解失败 + * - -1: 上一时刻关节角度输入为空 + * - -2: 目标位姿四元数不合法 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics(rm_robot_handle *handle, rm_inverse_kinematics_params_t params, float *q_out); + +/** + * @brief 计算逆运动学全解(当前仅支持六自由度机器人) + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param params 逆解输入参数结构体 + * @return rm_inverse_kinematics_all_solve_t 逆解的全解结构体 +*/ +RM_INTERFACE_EXPORT rm_inverse_kinematics_all_solve_t rm_algo_inverse_kinematics_all(rm_robot_handle *handle, rm_inverse_kinematics_params_t params); + +/** + * @brief 从多解中选取最优解(当前仅支持六自由度机器人) + * @param weight 权重,建议默认值为{1,1,1,1,1,1} + * @param params 待选解的全解结构体 + * @return int 最优解索引,选解结果为ik_solve.q_solve[i],如果没有合适的解返回-1(比如求出8组解,但是8组都有关节角度超限位,那么就返回-1) +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_select_ik_solve(float *weight, rm_inverse_kinematics_all_solve_t params); + + +/** + * @brief 检查逆解结果是否超出关节限位(当前仅支持六自由度机器人) + * @param q_solve 选解,单位:° + * @return int 0:未超限位,1~dof: 第i个关节超限位,-1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_position_limit(const float* const q_solve); + +/** + * @brief 检查逆解结果是否超速(当前仅支持六自由度机器人) + * @param dt 两帧数据之间的时间间隔,即控制周期,单位sec + * @param q_ref 参考关节角度或者第一帧数据角度,单位:° + * @param q_solve 求解结果,即下一帧要发送的角度 + * @return int 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_velocity_limit(float dt, const float* const q_ref, const float* const q_solve); + +/** + * @brief 根据参考位形计算臂角大小(仅支持RM75) + * @param q_ref 当前参考位形的关节角度,单位° + * @param arm_angle 计算结果,当前参考位形对应的臂角大小,单位° + * @return int + * 0: 求解成功 + * -1: 求解失败,或机型非RM75 + * -2: q_ref 输入参数非法 + */ +RM_INTERFACE_EXPORT int rm_algo_calculate_arm_angle_from_config_rm75(float *q_ref, float *arm_angle); + +/** + * @brief 臂角法求解RM75逆运动学 + * @param params rm_inverse_kinematics_params_t,逆解参数结构体 + * @param arm_angle 指定轴角大小,单位:° + * @param q_solve 求解结果,单位:° + * @return int + * 0: 求解成功 + * -1: 求解失败 + * -2: 求解结果超出限位 + * -3: 机型非RM75 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics_rm75_for_arm_angle(rm_inverse_kinematics_params_t params, float arm_angle, float *q_solve); + + + +/** + * @brief 通过分析雅可比矩阵最小奇异值, 判断机器人是否处于奇异状态 + * @param q 要判断的关节角度(机械零位描述),单位:° + * @param 最小奇异值阈值,若传NULL,则使用内部默认值,默认值为0.01(该值在0-1之间) + * @return 0:在当前阈值条件下正常 + * -1:表示在当前阈值条件下判断为奇异区 + * -2:表示计算失败 +*/ +RM_INTERFACE_EXPORT int rm_algo_universal_singularity_analyse(const float* const q, float singluar_value_limit); +/** + * @brief 恢复初始阈值(仅适用于解析法分析机器人奇异状态),阈值初始化为:limit_qe=10deg,limit_qw=10deg,limit_d = 0.05m +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_singularity_thresholds_init(); + +/** + * @brief 设置自定义阈值(仅适用于解析法分析机器人奇异状态) + * @param limit_qe 肘部奇异区域范围设置(即J3接近0的范围),unit:°,default: about 10deg + * @param limit_qw 腕部奇异区域范围设置(即J5接近0的范围),unit:°,default: about 10deg + * @param limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_set_singularity_thresholds(float limit_qe_algo, float limit_qw_algo, float limit_d_algo); + +/** + * @brief 获取自定义阈值(仅适用于解析法分析机器人奇异状态) + * + * @param limit_qe 肘部奇异区域范围获取(即J3接近0的范围), unit: °, default: about 10deg + * @param limit_qw 腕部奇异区域范围获取(即J5接近0的范围), unit: °, default: about 10deg + * @param limit_d 肩部奇异区域范围获取(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 + */ +RM_INTERFACE_EXPORT void rm_algo_kin_get_singularity_thresholds(float* limit_qe_algo, float* limit_qw_algo, float* limit_d_algo); + +/** + * @brief 解析法判断机器人是否处于奇异位形(仅支持六自由度) + * @param q 要判断的关节角度,单位:° + * @param distance 输出参数,返回腕部中心点到肩部奇异平面的距离,该值越接近0说明越接近肩部奇异,单位m,不需要时可传NULL + * @return 0表正常,-1表肩部奇异,-2表肘部奇异,-3表腕部奇异,-4仅支持6自由度机械臂 +*/ +RM_INTERFACE_EXPORT int rm_algo_kin_robot_singularity_analyse(const float* const q, float *distance); +/** + * @brief 设置工具包络球参数 + * @param toolSphere_i 工具包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_set_tool_envelope(const int toolSphere_i, rm_tool_sphere_t data); + +/** + * @brief 获取工具包络球参数 + * @param toolSphere_i 工具rm_get_tool_voltage包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_get_tool_envelope(const int toolSphere_i, rm_tool_sphere_t *data); +/** + * @brief 自碰撞检测 + * @param joint 要判断的关节角度,单位:° + * @return int + * 0: 无碰撞 + * 1: 发生碰撞,超出关节限位将被认为发生碰撞 + */ +RM_INTERFACE_EXPORT int rm_algo_safety_robot_self_collision_detection(float *joint); +/** + * @brief 机械臂正解函数 + * + * @param handle 机械臂控制句柄 + * @param joint + * + * @return rm_pose_t 目标位姿 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_forward_kinematics(rm_robot_handle *handle,const float* const joint); +/** + * @brief 欧拉角转四元数 + * + * @param eu 欧拉角 + * @return rm_quat_t 四元数 + */ +RM_INTERFACE_EXPORT rm_quat_t rm_algo_euler2quaternion(rm_euler_t eu); +/** + * @brief 四元数转欧拉角 + * + * @param qua 四元数 + * @return rm_euler_t 欧拉角 + */ +RM_INTERFACE_EXPORT rm_euler_t rm_algo_quaternion2euler(rm_quat_t qua); +/** + * @brief 欧拉角转旋转矩阵 + * + * @param state 欧拉角 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_euler2matrix(rm_euler_t state); +/** + * @brief 位姿转旋转矩阵 + * + * @param state 位姿 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_pos2matrix(rm_pose_t state); +/** + * @brief 旋转矩阵转位姿 + * + * @param matrix 旋转矩阵 + * @return rm_pose_t 位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_matrix2pos(rm_matrix_t matrix); +/** + * @brief 基坐标系转工作坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在基坐标系下位姿 + * @return rm_pose_t 基坐标系在工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_base2workframe(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 工作坐标系转基坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在工作坐标系下位姿 + * @return rm_pose_t 工作坐标系在基坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_workframe2base(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 计算环绕运动位姿 + * + * @param handle 机械臂控制句柄 + * @param curr_joint 当前关节角度 单位° + * @param rotate_axis 旋转轴: 1:x轴, 2:y轴, 3:z轴 + * @param rotate_angle 旋转角度: 旋转角度, 单位(度) + * @param choose_axis 指定计算时使用的坐标系 + * @return rm_pose_t 计算位姿结果 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_rotate_move(rm_robot_handle *handle,const float* const curr_joint, int rotate_axis, float rotate_angle, rm_pose_t choose_axis); +/** + * @brief 计算沿工具坐标系运动位姿 + * + * @param handle 机械臂控制句柄 + * @param curr_joint 当前关节角度,单位:度 + * @param move_lengthx 沿X轴移动长度,单位:米 + * @param move_lengthy 沿Y轴移动长度,单位:米 + * @param move_lengthz 沿Z轴移动长度,单位:米 + * @return rm_pose_t 工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_cartesian_tool(rm_robot_handle *handle,const float* const curr_joint, float move_lengthx, + float move_lengthy, float move_lengthz); + /** + * @brief 计算Pos和Rot沿某坐标系有一定的位移和旋转角度后,所得到的位姿数据 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param poseCurrent 当前时刻位姿(欧拉角形式) + * @param deltaPosAndRot 移动及旋转数组,位置移动(单位:m),旋转(单位:度) + * @param frameMode 坐标系模式选择 0:Work(work即可任意设置坐标系),1:Tool + * @return rm_pose_t 平移旋转后的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_pose_move(rm_robot_handle *handle,rm_pose_t poseCurrent, const float *deltaPosAndRot, int frameMode); +/** + * @brief 末端位姿转成工具位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_end 基于世界坐标系和默认工具坐标系的末端位姿 + * @return rm_pose_t 基于工作坐标系和工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_end2tool(rm_robot_handle *handle,rm_pose_t eu_end); +/** + * @brief 工具位姿转末端位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_tool 基于工作坐标系和工具坐标系的末端位姿 + * @return rm_pose_t 基于世界坐标系和默认工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_tool2end(rm_robot_handle *handle,rm_pose_t eu_tool); +/** + * @brief 获取DH参数 + * + * @return rm_DH_t DH参数 + */ +RM_INTERFACE_EXPORT rm_dh_t rm_algo_get_dh(); +/** + * @brief 设置DH参数 + * + * @param dh DH参数 + */ +RM_INTERFACE_EXPORT void rm_algo_set_dh(rm_dh_t dh); +/** @} */ // 结束算法组的定义 + +/*********************************************四代控制器新增接口*******************************************************/ + +/** + * @brief 查询轨迹列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list 轨迹列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_trajectory_file_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_trajectory_list_t *trajectory_list); +/** + * @brief 开始运行指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_run_trajectory(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 删除指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 保存轨迹到控制机器 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); + +/** + * @brief 设置机械臂急停状态 + * @param handle 机械臂控制句柄 + * @param state 急停状态,true:急停,false:恢复 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_arm_emergency_stop(rm_robot_handle *handle, bool state); +/** + * @brief 新增Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_add_modbus_tcp_master(rm_robot_handle *handle, rm_modbus_tcp_master_info_t master); +/** + * @brief 修改Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master 要修改的Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_update_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t master); +/** + * @brief 删除Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_modbus_tcp_master(rm_robot_handle *handle, const char *master_name); +/** + * @brief 查询Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t *master); +/** + * @brief 查询TCP主站列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list TCP主站列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_modbus_tcp_master_list_t *list); +/** + * @brief 设置控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_controller_rs485_mode(rm_robot_handle *handle, int controller_rs485_mode, int baudrate); +/** + * @brief 查询控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_rs485_mode_v4(rm_robot_handle *handle, int *controller_rs485_mode, int *baudrate); +/** + * @brief 设置工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_tool_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param tool_rs485_mode 0-代表modbus-RTU主站模式,1-代表灵巧手模式,2-代表夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_rs485_mode_v4(rm_robot_handle *handle, int *tool_rs485_mode, int *baudrate); +/** + * @brief Modbus RTU协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_status(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_holding_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_registers(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_status(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_holding_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_registers(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); + + +}; + +#endif // __cplusplus + +#endif // MY_CPP_WRAPPER_H \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_version.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_version.h new file mode 100755 index 0000000..8ce72a1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_version.h @@ -0,0 +1,16 @@ + +#ifndef RM_VERSION_H +#define RM_VERSION_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define SDK_VERSION ("1.1.0") + +#ifdef __cplusplus +} +#endif + +#endif + \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_63_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_63_driver.launch.py new file mode 100755 index 0000000..7ee4e48 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_63_driver.launch.py @@ -0,0 +1,26 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + ld = LaunchDescription() + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_63_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + rm_63_driver = Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + ld.add_action(rm_63_driver) + + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_65_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_65_driver.launch.py new file mode 100755 index 0000000..4e0e866 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_65_driver.launch.py @@ -0,0 +1,27 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_65_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + return LaunchDescription([ + + Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_75_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_75_driver.launch.py new file mode 100755 index 0000000..abf44b7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_75_driver.launch.py @@ -0,0 +1,27 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_75_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + return LaunchDescription([ + + Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco63_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco63_driver.launch.py new file mode 100755 index 0000000..8908f2f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco63_driver.launch.py @@ -0,0 +1,26 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + ld = LaunchDescription() + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_eco63_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + rm_eco63_driver = Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + ld.add_action(rm_eco63_driver) + + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco65_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco65_driver.launch.py new file mode 100755 index 0000000..9c8a187 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_eco65_driver.launch.py @@ -0,0 +1,26 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + ld = LaunchDescription() + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_eco65_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + rm_eco65_driver = Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + ld.add_action(rm_eco65_driver) + + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_gen72_driver.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_gen72_driver.launch.py new file mode 100755 index 0000000..242c544 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/launch/rm_gen72_driver.launch.py @@ -0,0 +1,27 @@ +import launch +import os +import yaml +import launch_ros +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + + arm_config = os.path.join(get_package_share_directory('rm_driver'),'config','rm_gen72_config.yaml') + + with open(arm_config,'r') as f: + params = yaml.safe_load(f)["rm_driver"]["ros__parameters"] + + return LaunchDescription([ + + Node( + package= "rm_driver", #功能包。 + executable= "rm_driver", #节点。 + parameters= [arm_config + ], #接入参数文件 + output= 'screen' + ) + + ]) \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/lib_install.sh b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/lib_install.sh new file mode 100755 index 0000000..9c15c88 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/lib_install.sh @@ -0,0 +1,53 @@ +#!/bin/bash +# Version: 1.0 +# Date: $(date +%Y-%m-%d) +# Author: Your Name +# Description: Install libapi_cpp.so for target system + +set -e + +# Check sudo privileges +if [ "$(id -u)" != "0" ]; then + echo "This script must be run with sudo. Example: sudo $0" + exit 1 +fi + +# Cleanup old library +echo "Removing existing libapi_cpp.so..." +sudo rm -f /usr/local/lib/libapi_cpp.so* 2>/dev/null || true + +if [ $(uname -m) = "x86_64" ]; then + if [ -f "./linux_x86_c++_v1.1.1/libapi_cpp.so" ];then + echo "find x86 file" + cd linux_x86_c++* + sudo cp ./libapi_cpp.so /usr/local/lib/ + sudo cp ./libapi_cpp.so .. + cd .. + else + echo "Error: x86libapi_cpp.so not found in current directory!" + exit 1 + fi +else + if [ -f "./linux_arm64_c++*/libapi_cpp.so" ];then + echo "find arm file" + cd linux_arm64_c++_v1.1.0 + sudo cp ./libapi_cpp.so /usr/local/lib/ + sudo cp ./libapi_cpp.so .. + cd .. + else + echo "Error: arm64libapi_cpp.so not found in current directory!" + exit 1 + fi +fi + +# Configure library path +echo "Updating system library configuration..." +if ! grep -q "/usr/local/lib" /etc/ld.so.conf; then + echo "/usr/local/lib" | sudo tee -a /etc/ld.so.conf +fi + +# Update library cache +sudo /sbin/ldconfig + +# Completion message +echo -e "\n\033[1;32m[SUCCESS] libapi_cpp.so installed successfully!\033[0m" diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/libapi_cpp.so b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/libapi_cpp.so new file mode 100755 index 0000000..a27aabd Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/libapi_cpp.so differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_arm64_c++_v1.1.0/libapi_cpp.so b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_arm64_c++_v1.1.0/libapi_cpp.so new file mode 100755 index 0000000..3ba689a Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_arm64_c++_v1.1.0/libapi_cpp.so differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_x86_c++_v1.1.1/libapi_cpp.so b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_x86_c++_v1.1.1/libapi_cpp.so new file mode 100755 index 0000000..a27aabd Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/lib/linux_x86_c++_v1.1.1/libapi_cpp.so differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/package.xml new file mode 100755 index 0000000..e8e2e4f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/package.xml @@ -0,0 +1,23 @@ + + + + rm_driver + 0.0.0 + TODO: Package description + xtark + TODO: License declaration + + ament_cmake + + rclcpp + + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/src/rm_driver.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/src/rm_driver.cpp new file mode 100755 index 0000000..26e5cfd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/src/rm_driver.cpp @@ -0,0 +1,3773 @@ +// Copyright (c) 2024 RealMan Intelligent Ltd +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#include "rm_driver.h" + +using namespace std::chrono_literals; + +static void my_handler(int sig) // can be called asynchronously +{ + (void)sig; + ctrl_flag = true; // set flag +} + +//连接机械臂网络 +int Arm_Socket_Start_Connect(void) +{ + int Arm_Socket; //机械臂TCp网络通信套接字 + int Arm_connect; //机械臂TCP连接状态 + + Arm_Socket = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + if (Arm_Socket <= 0) + { + return 2; + } + + struct sockaddr_in serAddr; + // struct timeval tm; + serAddr.sin_family = AF_INET; + serAddr.sin_port = htons(tcp_port); + serAddr.sin_addr.s_addr = inet_addr(tcp_ip); + int flag = 0; + int old_flag = 0; + flag |= O_NONBLOCK; + // 设置为非阻塞模式 + old_flag = flag = fcntl(Arm_Socket, F_SETFL, O_NONBLOCK ); + // 查看连接状态 + Arm_connect = connect(Arm_Socket, (struct sockaddr *)&serAddr, sizeof(serAddr)); + // ROS_INFO("Arm_connect=%d\n",Arm_connect); + if (Arm_connect != 0) + { + if(errno != EINPROGRESS) //connect返回错误。 + { + std::cout<<"Arm_connect="<< Arm_connect <<"connect failed"<id < 0) + { + rm_delete_robot_arm(robot_handle); + std::cout<<"arm connect err..."<< robot_handle << std::endl; + } + // else if(robot_handle != NULL) + // { + // std::cout<<"connect success, arm id :"<id<joint[i] * RAD_DEGREE; + } + if(msg->dof == 7) + { + joint[6] = msg->joint[6] * RAD_DEGREE; + } + v = msg->speed; + trajectory_connect = msg->trajectory_connect; + block = msg->block; + //res = Rm_Api.Service_Movej_Cmd(m_sockhand, joint, v ,0, trajectory_connect, block); + res = Rm_Api.rm_movej(robot_handle, joint, v ,0, trajectory_connect, block); + movej_data.data = res; + if(movej_data.data == 0) + { + movej_result.data = true; + this->MoveJ_Cmd_Result->publish(movej_result); + } + else + { + movej_result.data = false; + this->MoveJ_Cmd_Result->publish(movej_result); + RCLCPP_INFO (this->get_logger(),"MoveJ error code is %d\n",movej_data.data); + } +} + +void RmArm::Arm_MoveL_Callback(rm_ros_interfaces::msg::Movel::SharedPtr msg) +{ + rm_pose_t pose; + int v; + bool block; + int32_t res; + std_msgs::msg::UInt32 movel_data; + std_msgs::msg::Bool movel_result; + rm_quat_t rec_pose; + rm_euler_t tarns_euler; + int trajectory_connect; + + pose.position.x = msg->pose.position.x; + pose.position.y = msg->pose.position.y; + pose.position.z = msg->pose.position.z; + rec_pose.w = msg->pose.orientation.w; + rec_pose.x = msg->pose.orientation.x; + rec_pose.y = msg->pose.orientation.y; + rec_pose.z = msg->pose.orientation.z; + // tarns_euler = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose); + tarns_euler = Rm_Api.rm_algo_quaternion2euler(rec_pose); + pose.euler.rx = tarns_euler.rx; + pose.euler.ry = tarns_euler.ry; + pose.euler.rz = tarns_euler.rz; + v = msg->speed; + block = msg->block; + trajectory_connect = msg->trajectory_connect; + // res = Rm_Api.Service_Movel_Cmd(m_sockhand, pose, v ,0, trajectory_connect, block); + res = Rm_Api.rm_movel(robot_handle, pose, v ,0, trajectory_connect, block); + movel_data.data = res; + if(movel_data.data == 0) + { + movel_result.data = true; + this->MoveL_Cmd_Result->publish(movel_result); + } + else + { + movel_result.data = false; + this->MoveL_Cmd_Result->publish(movel_result); + RCLCPP_INFO (this->get_logger(),"MoveL error code is %d\n",movel_data.data); + } +} +void RmArm::Arm_MoveL_Offset_Callback(rm_ros_interfaces::msg::Moveloffset::SharedPtr msg) +{ + rm_pose_t pose; + int v,r; + bool frame_type,block; + int32_t res; + std_msgs::msg::UInt32 movel_data; + std_msgs::msg::Bool movel_result; + rm_quat_t rec_pose; + rm_euler_t tarns_euler; + int trajectory_connect; + pose.position.x = msg->pose.position.x; + pose.position.y = msg->pose.position.y; + pose.position.z = msg->pose.position.z; + rec_pose.w = msg->pose.orientation.w; + rec_pose.x = msg->pose.orientation.x; + rec_pose.y = msg->pose.orientation.y; + rec_pose.z = msg->pose.orientation.z; + tarns_euler = Rm_Api.rm_algo_quaternion2euler(rec_pose); + pose.euler.rx = tarns_euler.rx; + pose.euler.ry = tarns_euler.ry; + pose.euler.rz = tarns_euler.rz; + v = msg->speed; + r = msg->r; + block = msg->block; + frame_type = msg->frame_type; + trajectory_connect = msg->trajectory_connect; + res = Rm_Api.rm_movel_offset(robot_handle, pose, v ,r, trajectory_connect, frame_type, block); + movel_data.data = res; + if(movel_data.data == 0) + { + movel_result.data = true; + this->MoveL_offset_Cmd_Result->publish(movel_result); + } + else + { + movel_result.data = false; + this->MoveL_offset_Cmd_Result->publish(movel_result); + RCLCPP_INFO (this->get_logger(),"MoveL error code is %d\n",movel_data.data); + } +} + +void RmArm::Arm_MoveC_Callback(rm_ros_interfaces::msg::Movec::SharedPtr msg) +{ + + rm_pose_t pose_via, pose_to; + int v,loop; + int32_t res; + std_msgs::msg::UInt32 movec_data; + std_msgs::msg::Bool movec_result; + rm_quat_t rec_pose_via, rec_pose_to; + rm_euler_t tarns_euler_via, tarns_euler_to; + int trajectory_connect; + bool block; + + pose_via.position.x = msg->pose_mid.position.x; + pose_via.position.y = msg->pose_mid.position.y; + pose_via.position.z = msg->pose_mid.position.z; + rec_pose_via.w = msg->pose_mid.orientation.w; + rec_pose_via.x = msg->pose_mid.orientation.x; + rec_pose_via.y = msg->pose_mid.orientation.y; + rec_pose_via.z = msg->pose_mid.orientation.z; + // tarns_euler_via = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose_via); + tarns_euler_via = Rm_Api.rm_algo_quaternion2euler(rec_pose_via); + pose_via.euler.rx = tarns_euler_via.rx; + pose_via.euler.ry = tarns_euler_via.ry; + pose_via.euler.rz = tarns_euler_via.rz; + + pose_to.position.x = msg->pose_end.position.x; + pose_to.position.y = msg->pose_end.position.y; + pose_to.position.z = msg->pose_end.position.z; + rec_pose_to.w = msg->pose_end.orientation.w; + rec_pose_to.x = msg->pose_end.orientation.x; + rec_pose_to.y = msg->pose_end.orientation.y; + rec_pose_to.z = msg->pose_end.orientation.z; + // tarns_euler_to = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose_to); + tarns_euler_to = Rm_Api.rm_algo_quaternion2euler(rec_pose_to); + pose_to.euler.rx = tarns_euler_to.rx; + pose_to.euler.ry = tarns_euler_to.ry; + pose_to.euler.rz = tarns_euler_to.rz; + + v = msg->speed; + loop = msg->loop; + block = msg->block; + trajectory_connect = msg->trajectory_connect; + // res = Rm_Api.Service_Movec_Cmd(m_sockhand, pose_via, pose_to, v, 0, loop, trajectory_connect, block); + res = Rm_Api.rm_movec(robot_handle, pose_via, pose_to, v, 0, loop, trajectory_connect, block); + movec_data.data = res; + if(movec_data.data == 0) + { + movec_result.data = true; + this->MoveC_Cmd_Result->publish(movec_result); + } + else + { + movec_result.data = false; + this->MoveC_Cmd_Result->publish(movec_result); + RCLCPP_INFO (this->get_logger(),"MoveC error code is %d\n",movec_data.data); + } +} + +void RmArm::Arm_Movej_CANFD_Callback(rm_ros_interfaces::msg::Jointpos::SharedPtr msg) +{ + float joint[7]; + bool follow; + float expand; + int32_t res; + int trajectory_mode; + int radio; + std_msgs::msg::UInt32 movej_CANFD_data; + + for(int i = 0; i < 6; i++) + { + joint[i] = msg->joint[i] * RAD_DEGREE; + } + if(msg->dof == 7) + { + joint[6] = msg->joint[6] * RAD_DEGREE; + } + + follow = msg->follow; + expand = msg->expand * RAD_DEGREE; + trajectory_mode = trajectory_mode_; + radio = radio_; + //std::cout<<"Service_Movej_CANFD_With_Radio is run!!!!"<get_logger(),"Movej CANFD error code is %d\n",movej_CANFD_data.data); + } +} + +void RmArm::Arm_Movej_CANFD_Custom_Callback(rm_ros_interfaces::msg::Jointposcustom::SharedPtr msg) +{ + float joint[7]; + bool follow; + float expand; + int32_t res; + int trajectory_mode; + int radio; + std_msgs::msg::UInt32 movej_CANFD_data; + + for(int i = 0; i < 6; i++) + { + joint[i] = msg->joint[i] * RAD_DEGREE; + } + if(msg->dof == 7) + { + joint[6] = msg->joint[6] * RAD_DEGREE; + } + + follow = msg->follow; + expand = msg->expand * RAD_DEGREE; + trajectory_mode = msg->trajectory_mode; + radio = msg->radio; + // std::cout<<"Service_Movej_CANFD_Trajectory is run!!!!"<get_logger(),"Movej CANFD error code is %d\n",movej_CANFD_data.data); + } +} + +void RmArm::Arm_Movep_CANFD_Callback(rm_ros_interfaces::msg::Cartepos::SharedPtr msg) +{ + + rm_pose_t pose; + bool follow; + int32_t res; + std_msgs::msg::UInt32 movep_CANFD_data; + rm_quat_t rec_pose; + rm_euler_t tarns_euler; + int trajectory_mode; + int radio; + + pose.position.x = msg->pose.position.x; + pose.position.y = msg->pose.position.y; + pose.position.z = msg->pose.position.z; + rec_pose.w = msg->pose.orientation.w; + rec_pose.x = msg->pose.orientation.x; + rec_pose.y = msg->pose.orientation.y; + rec_pose.z = msg->pose.orientation.z; + // tarns_euler = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose); + tarns_euler = Rm_Api.rm_algo_quaternion2euler(rec_pose); + pose.euler.rx = tarns_euler.rx; + pose.euler.ry = tarns_euler.ry; + pose.euler.rz = tarns_euler.rz; + follow = msg->follow; + trajectory_mode = trajectory_mode_; + radio = radio_; + + // res = Rm_Api.Service_Movep_CANFD_With_Radio(m_sockhand, pose, follow, trajectory_mode, radio); + res = Rm_Api.rm_movep_canfd(robot_handle, pose, follow, trajectory_mode, radio); + + movep_CANFD_data.data = res; + if(movep_CANFD_data.data != 0) + { + RCLCPP_INFO (this->get_logger(),"Movep CANFD error code is %d\n",movep_CANFD_data.data); + } +} + +void RmArm::Arm_Movep_CANFD_Custom_Callback(rm_ros_interfaces::msg::Carteposcustom::SharedPtr msg) +{ + rm_pose_t pose; + bool follow; + int32_t res; + std_msgs::msg::UInt32 movep_CANFD_data; + rm_quat_t rec_pose; + rm_euler_t tarns_euler; + int trajectory_mode; + int radio; + + pose.position.x = msg->pose.position.x; + pose.position.y = msg->pose.position.y; + pose.position.z = msg->pose.position.z; + rec_pose.w = msg->pose.orientation.w; + rec_pose.x = msg->pose.orientation.x; + rec_pose.y = msg->pose.orientation.y; + rec_pose.z = msg->pose.orientation.z; + // tarns_euler = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose); + tarns_euler = Rm_Api.rm_algo_quaternion2euler(rec_pose); + pose.euler.rx = tarns_euler.rx; + pose.euler.ry = tarns_euler.ry; + pose.euler.rz = tarns_euler.rz; + follow = msg->follow; + trajectory_mode = msg->trajectory_mode; + radio = msg->radio; + std::cout<<"Service_Movep_CANFD_Trajectory is run!!!!"<get_logger(),"Movep CANFD error code is %d\n",movep_CANFD_data.data); + } +} + +void RmArm::Arm_MoveJ_P_Callback(rm_ros_interfaces::msg::Movejp::SharedPtr msg) +{ + + rm_pose_t pose; + int v; + bool block; + int32_t res; + std_msgs::msg::UInt32 movej_p_data; + std_msgs::msg::Bool movej_p_result; + rm_quat_t rec_pose; + rm_euler_t tarns_euler; + int trajectory_connect; + + pose.position.x = msg->pose.position.x; + pose.position.y = msg->pose.position.y; + pose.position.z = msg->pose.position.z; + rec_pose.w = msg->pose.orientation.w; + rec_pose.x = msg->pose.orientation.x; + rec_pose.y = msg->pose.orientation.y; + rec_pose.z = msg->pose.orientation.z; + // tarns_euler = Rm_Api.Service_Algo_Quaternion2Euler(rec_pose); + tarns_euler = Rm_Api.rm_algo_quaternion2euler(rec_pose); + pose.euler.rx = tarns_euler.rx; + pose.euler.ry = tarns_euler.ry; + pose.euler.rz = tarns_euler.rz; + v = msg->speed; + trajectory_connect = msg->trajectory_connect; + block = msg->block; + // res = Rm_Api.Service_Movej_P_Cmd(m_sockhand, pose, v ,0, trajectory_connect, block); + res = Rm_Api.rm_movej_p(robot_handle, pose, v ,0, trajectory_connect, block); + movej_p_data.data = res; + if(movej_p_data.data == 0) + { + movej_p_result.data = true; + this->MoveJ_P_Cmd_Result->publish(movej_p_result); + } + else + { + movej_p_result.data = false; + this->MoveJ_P_Cmd_Result->publish(movej_p_result); + RCLCPP_INFO (this->get_logger(),"Movej_p error code is %d\n",movej_p_data.data); + } +} + +void RmArm::Arm_Move_Stop_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + copy = msg; + // bool block; + int32_t res; + std_msgs::msg::UInt32 move_stop_data; + std_msgs::msg::Bool move_stop_result; + + // block = msg->data; + // res = Rm_Api.Service_Move_Stop_Cmd(m_sockhand, block); + res = Rm_Api.rm_set_arm_stop(robot_handle); + move_stop_data.data = res; + if(move_stop_data.data == 0) + { + move_stop_result.data = true; + this->Move_Stop_Cmd_Result->publish(move_stop_result); + } + else + { + move_stop_result.data = false; + this->Move_Stop_Cmd_Result->publish(move_stop_result); + RCLCPP_INFO (this->get_logger(),"Move stop error code is %d\n",move_stop_data.data); + } +} + +void RmArm::Arm_Emergency_Stop_Callback(const rm_ros_interfaces::msg::Stop::SharedPtr msg) +{ + // copy = msg; + int32_t res; + bool state; + state = msg->state; + std_msgs::msg::UInt32 move_stop_data; + std_msgs::msg::Bool move_stop_result; + res = Rm_Api.rm_set_arm_emergency_stop(robot_handle,state); + move_stop_data.data = res; + if(move_stop_data.data == 0) + { + move_stop_result.data = true; + this->Arm_Emergency_Stop_Cmd_Result->publish(move_stop_result); + } + else + { + move_stop_result.data = false; + this->Arm_Emergency_Stop_Cmd_Result->publish(move_stop_result); + RCLCPP_INFO (this->get_logger(),"Emergency stop error code is %d\n",move_stop_data.data); + } +} + + +void RmArm::Set_Joint_Teach_Callback(rm_ros_interfaces::msg::Jointteach::SharedPtr msg) +{ + int num; + int direction; + int v; + // bool block; + int32_t res; + std_msgs::msg::UInt32 joint_teach_data; + std_msgs::msg::Bool joint_teach_result; + + num = msg->num; + direction = msg->direction; + v = msg->speed; + // block = msg->block; + + // res = Rm_Api.Service_Joint_Teach_Cmd(m_sockhand, num, direction, v , block); + res = Rm_Api.rm_set_joint_teach(robot_handle, num, direction, v); + joint_teach_data.data = res; + if(joint_teach_data.data == 0) + { + joint_teach_result.data = true; + this->Set_Joint_Teach_Cmd_Result->publish(joint_teach_result); + } + else + { + joint_teach_result.data = false; + this->Set_Joint_Teach_Cmd_Result->publish(joint_teach_result); + RCLCPP_INFO (this->get_logger(),"Joint_Teach error code is %d\n",joint_teach_data.data); + } +} + +void RmArm::Set_Pos_Teach_Callback(rm_ros_interfaces::msg::Posteach::SharedPtr msg) +{ + int type; + int direction; + int v; + // bool block; + int32_t res; + std_msgs::msg::UInt32 pos_teach_data; + std_msgs::msg::Bool pos_teach_result; + + type = msg->type; + direction = msg->direction; + v = msg->speed; + // block = msg->block; + + // res = Rm_Api.Service_Pos_Teach_Cmd(m_sockhand, (POS_TEACH_MODES)type, direction, v , block); + res = Rm_Api.rm_set_pos_teach(robot_handle, (rm_pos_teach_type_e)type, direction, v); + pos_teach_data.data = res; + if(pos_teach_data.data == 0) + { + pos_teach_result.data = true; + this->Set_Pos_Teach_Cmd_Result->publish(pos_teach_result); + } + else + { + pos_teach_result.data = false; + this->Set_Pos_Teach_Cmd_Result->publish(pos_teach_result); + RCLCPP_INFO (this->get_logger(),"Pos_Teach error code is %d\n",pos_teach_data.data); + } +} + +void RmArm::Set_Ort_Teach_Callback(rm_ros_interfaces::msg::Ortteach::SharedPtr msg) +{ + int type; + int direction; + int v; + // bool block; + int32_t res; + std_msgs::msg::UInt32 ort_teach_data; + std_msgs::msg::Bool ort_teach_result; + + type = msg->type; + direction = msg->direction; + v = msg->speed; + // block = msg->block; + + // res = Rm_Api.Service_Ort_Teach_Cmd(m_sockhand, (ORT_TEACH_MODES)type, direction, v , block); + res = Rm_Api.rm_set_ort_teach(robot_handle, (rm_ort_teach_type_e)type, direction, v ); + ort_teach_data.data = res; + if(ort_teach_data.data == 0) + { + ort_teach_result.data = true; + this->Set_Ort_Teach_Cmd_Result->publish(ort_teach_result); + } + else + { + ort_teach_result.data = false; + this->Set_Ort_Teach_Cmd_Result->publish(ort_teach_result); + RCLCPP_INFO (this->get_logger(),"Ort_Teach error code is %d\n",ort_teach_data.data); + } +} + +void RmArm::Set_Stop_Teach_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + copy = msg; + // bool block; + int32_t res; + std_msgs::msg::UInt32 stop_teach_data; + std_msgs::msg::Bool stop_teach_result; + + // block = msg->data; + + // res = Rm_Api.Service_Teach_Stop_Cmd(m_sockhand, block); + res = Rm_Api.rm_set_stop_teach(robot_handle); + stop_teach_data.data = res; + if(stop_teach_data.data == 0) + { + stop_teach_result.data = true; + this->Set_Stop_Teach_Cmd_Result->publish(stop_teach_result); + } + else + { + stop_teach_result.data = false; + this->Set_Stop_Teach_Cmd_Result->publish(stop_teach_result); + RCLCPP_INFO (this->get_logger(),"Stop_Teach error code is %d\n",stop_teach_data.data); + } +} + + +void RmArm::Arm_Get_Realtime_Push_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + rm_ros_interfaces::msg::Setrealtimepush Setrealtime_msg; + copy = msg; + rm_realtime_push_config_t config; + // res = Rm_Api.Service_Get_Realtime_Push(m_sockhand, &config); + res = Rm_Api.rm_get_realtime_push(robot_handle, &config); + if(res == 0) + { + Setrealtime_msg.cycle = config.cycle; + Setrealtime_msg.port = config.port; + Setrealtime_msg.force_coordinate = config.force_coordinate; + Setrealtime_msg.ip = config.ip; + Setrealtime_msg.hand_enable = config.custom_config.hand_state; + Setrealtime_msg.joint_speed_enable = config.custom_config.joint_speed; + Setrealtime_msg.lift_state_enable = config.custom_config.lift_state; + Setrealtime_msg.expand_state_enable = config.custom_config.expand_state; + Setrealtime_msg.arm_current_status_enable = config.custom_config.arm_current_status; + Setrealtime_msg.aloha_state_enable = config.custom_config.aloha_state; + udp_hand_g = config.custom_config.hand_state; + this->Get_Realtime_Push_Result->publish(Setrealtime_msg); + } + else + RCLCPP_INFO (this->get_logger(),"The get_realtime_push error code is %d\n",res); +} + +void RmArm::Arm_Set_Realtime_Push_Callback(const rm_ros_interfaces::msg::Setrealtimepush::SharedPtr msg) +{ + rm_realtime_push_config_t config; + int32_t res; + std_msgs::msg::Bool set_realtime_result; + config.port = msg->port ; + config.cycle = msg->cycle; + config.force_coordinate = msg->force_coordinate; + config.enable = true; + strcpy(config.ip,msg->ip.data()); + rm_udp_custom_config_t config_enable; + config_enable.expand_state = msg->expand_state_enable; + config_enable.hand_state = msg->hand_enable; + udp_hand_g = msg->hand_enable; + config_enable.joint_speed = msg->joint_speed_enable; + config_enable.lift_state = msg->lift_state_enable; + config_enable.arm_current_status = msg->arm_current_status_enable; + config_enable.aloha_state = msg->aloha_state_enable; + config_enable.plus_base = msg->plus_base_enable; + rm_plus_base_g = msg->plus_base_enable; + config_enable.plus_state = msg->plus_state_enable; + rm_plus_state_g = msg->plus_state_enable; + config.custom_config = config_enable; + // res = Rm_Api.Service_Set_Realtime_Push(m_sockhand, config); + res = Rm_Api.rm_set_realtime_push(robot_handle, config); + if(res == 0) + { + set_realtime_result.data = true; + this->Set_Realtime_Push_Result->publish(set_realtime_result); + } + else + { + set_realtime_result.data = false; + this->Set_Realtime_Push_Result->publish(set_realtime_result); + RCLCPP_INFO (this->get_logger(),"The set_realtime_push error code is %d\n",res); + } +} + +void RmArm::Set_UDP_Configuration(int udp_cycle, int udp_port, int udp_force_coordinate, std::string udp_ip, bool hand, bool rm_plus_base, bool rm_plus_state) +{ + int32_t res; + rm_realtime_push_config_t config; + config.port = udp_port ; + config.cycle = udp_cycle/5; + config.force_coordinate = udp_force_coordinate; + config.enable = true; + strcpy(config.ip,udp_ip.data()); + rm_udp_custom_config_t config_enable; + config_enable.expand_state = 0; + config_enable.hand_state = hand; + udp_hand_g = hand; + config_enable.joint_speed = 0; + config_enable.lift_state = 0; + config_enable.aloha_state = 0; + config_enable.plus_base = rm_plus_base; + rm_plus_base_g = rm_plus_base; + config_enable.plus_state = rm_plus_state; + rm_plus_state_g = rm_plus_state; + config_enable.arm_current_status = 0; + config.custom_config = config_enable; + // res = Rm_Api.Service_Set_Realtime_Push(m_sockhand, config); + res = Rm_Api.rm_set_realtime_push(robot_handle, config); + if(res == 0) + { + RCLCPP_INFO (this->get_logger(),"UDP_Configuration is cycle:%dms,port:%d,force_coordinate:%d,ip:%s,hand:%d,rm_plus_base:%d,rm_plus_state:%d\n", udp_cycle, udp_port, udp_force_coordinate, udp_ip.c_str(),udp_hand_g,rm_plus_base_g,rm_plus_state_g); + } + else + { + RCLCPP_INFO (this->get_logger(),"The set_realtime_push error code is %d\n",res); + } +} + +void RmArm::Get_Arm_Version() +{ + // ArmSoftwareInfo arm_software_info; + rm_arm_software_version_t arm_software_info; + char product_version[100]; + int32_t res; + //res = Rm_Api.Service_Get_Arm_Software_Info(m_sockhand, &arm_software_info); + res = Rm_Api.rm_get_arm_software_info(robot_handle, &arm_software_info); + if(res == 0) + { + RCLCPP_INFO (this->get_logger(),"product_version = %s",arm_software_info.product_version); + strcpy(product_version, arm_software_info.product_version); + Udp_RM_Joint.control_version = 1; + for(int i=0;i<10;i++) + { + if(product_version[i]=='F') + { + Udp_RM_Joint.control_version = 2; + } + } + // RCLCPP_INFO (this->get_logger(),"control_version = %d",Udp_RM_Joint.control_version); + } + else + { + RCLCPP_INFO (this->get_logger(),"Service_Get_Arm_Software_Version error = %d",res); + } +} + +void RmArm::Get_Controller_Version() +{ + rm_robot_info_t robot_info; + int32_t res; + res = Rm_Api.rm_get_robot_info(robot_handle, &robot_info); + if(res == 0) + { + controller_version = robot_info.robot_controller_version; + RCLCPP_INFO (this->get_logger(),"controller version : %d",controller_version); + + } + else + { + RCLCPP_INFO (this->get_logger(),"Service_Get_Arm_Software_Version error = %d",res); + } +} + +// 机械臂固件版本信息查询,在Api中去掉了 +// void RmArm::Arm_Get_Arm_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg) +// { + // char plan_version[50]; + // char ctrl_version[50]; + // char kernal1[50]; + // char kernal2[50]; + // char product_version[50]; +// int32_t res; +// rm_ros_interfaces::msg::Armsoftversion Armsoftversion_msg; +// copy = msg; +// res = Rm_Api.Service_Get_Arm_Software_Version(m_sockhand, plan_version, ctrl_version, kernal1, kernal2, product_version); +// if(res == 0) +// { +// Armsoftversion_msg.planversion = plan_version; +// Armsoftversion_msg.ctrlversion = ctrl_version; +// Armsoftversion_msg.kernal1 = kernal1; +// Armsoftversion_msg.kernal2 = kernal2; +// Armsoftversion_msg.productversion = product_version; +// this->Get_Arm_Software_Version_Result->publish(Armsoftversion_msg); +// } +// else +// { + // RCLCPP_INFO (this->get_logger(),"The error code is %d\n",res); +// } + +// } + +// 20250425:在适配四代控制器时又选择保留 +void RmArm::Arm_Get_Arm_Software_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + rm_arm_software_version_t arm_software_info; + memset(&arm_software_info, 0, sizeof(arm_software_info)); + int32_t res; + copy = msg; + res = Rm_Api.rm_get_arm_software_info(robot_handle, &arm_software_info); + // res = Rm_Api.Service_Get_Arm_Software_Version(m_sockhand, plan_version, ctrl_version, kernal1, kernal2, product_version); + if(res == 0) + { + if(controller_version==3){ + rm_ros_interfaces::msg::Armsoftversion Armsoftversion_msg; + Armsoftversion_msg.plan_info.version = arm_software_info.plan_info.version; + Armsoftversion_msg.plan_info.build_time = arm_software_info.plan_info.build_time; + Armsoftversion_msg.ctrl_info.build_time = arm_software_info.ctrl_info.build_time; + Armsoftversion_msg.ctrl_info.version = arm_software_info.ctrl_info.version; + Armsoftversion_msg.product_version = arm_software_info.product_version; + Armsoftversion_msg.controller_version = arm_software_info.robot_controller_version; + Armsoftversion_msg.algorithm_info = arm_software_info.algorithm_info.version; + Armsoftversion_msg.dynamic_info = arm_software_info.dynamic_info.model_version; + Armsoftversion_msg.state = true; + this->Get_Arm_Software_Version_Result->publish(Armsoftversion_msg); + } + if(controller_version==4){ + rm_ros_interfaces::msg::Armsoftversion Armsoftversion_msg; + Armsoftversion_msg.algorithm_info = arm_software_info.algorithm_info.version; + Armsoftversion_msg.ctrl_info.build_time = arm_software_info.ctrl_info.build_time; + Armsoftversion_msg.ctrl_info.version = arm_software_info.ctrl_info.version; + Armsoftversion_msg.product_version = arm_software_info.product_version; + Armsoftversion_msg.controller_version = arm_software_info.robot_controller_version; + Armsoftversion_msg.com_info.build_time = arm_software_info.com_info.build_time; + Armsoftversion_msg.com_info.version = arm_software_info.com_info.version; + Armsoftversion_msg.program_info.build_time = arm_software_info.program_info.build_time; + Armsoftversion_msg.program_info.version = arm_software_info.program_info.version; + Armsoftversion_msg.state = true; + this->Get_Arm_Software_Version_Result->publish(Armsoftversion_msg); + } + } + else + { + rm_ros_interfaces::msg::Armsoftversion Armsoftversion_msg; + Armsoftversion_msg.state = false; + this->Get_Arm_Software_Version_Result->publish(Armsoftversion_msg); + RCLCPP_INFO (this->get_logger(),"The get_arm_software error code is %d\n",res); + } + +} + +void RmArm::Arm_Get_Robot_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + rm_robot_info_t arm_robot_info; + memset(&arm_robot_info, 0, sizeof(arm_robot_info)); + int32_t res; + rm_ros_interfaces::msg::RobotInfo robotinfo_msg; + copy = msg; + res = Rm_Api.rm_get_robot_info(robot_handle, &arm_robot_info); + if(res == 0) + { + robotinfo_msg.arm_dof = arm_robot_info.arm_dof; + robotinfo_msg.arm_model = arm_robot_info.arm_model; + robotinfo_msg.force_type = arm_robot_info.force_type; + robotinfo_msg.robot_controller_version = arm_robot_info.robot_controller_version; + robotinfo_msg.state = true; + this->Get_Robot_Info_Result->publish(robotinfo_msg); + } + else + { + robotinfo_msg.state = false; + this->Get_Robot_Info_Result->publish(robotinfo_msg); + RCLCPP_INFO (this->get_logger(),"The robot info error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Joint_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + int joint_software_info[7]; + rm_ros_interfaces::msg::Jointversion jointsoftwareinfo; + rm_version_t joint_version[7] = {0}; + copy = msg; + res = Rm_Api.rm_get_joint_software_version(robot_handle, joint_software_info,joint_version); + if(res == 0) + { + if(controller_version==3){ + for(int i=0;i<7;i++){ + jointsoftwareinfo.joint_version[i] = std::to_string(joint_software_info[i]); //这里需要先转换成十六进制再转换成字符串 + } + } + if(controller_version==4){ + for(int i=0;i<7;i++){ + jointsoftwareinfo.joint_version[i] = joint_version[i].version; + } + } + jointsoftwareinfo.state = true; + this->Get_Joint_Software_Version_Result->publish(jointsoftwareinfo); + } + else + { + jointsoftwareinfo.state = true; + this->Get_Joint_Software_Version_Result->publish(jointsoftwareinfo); + RCLCPP_INFO (this->get_logger(),"The joint software info error code is %d\n",res); + } +} +void RmArm::Arm_Get_Tool_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + rm_version_t end_v; + int tool_software_info; + // std_msgs::msg::String toolsoftwareinfo; + rm_ros_interfaces::msg::Toolsoftwareversionv4 toolsoftwareinfo; + copy = msg; + res = Rm_Api.rm_get_tool_software_version(robot_handle, &tool_software_info,&end_v); + if(res == 0) + { + if(controller_version==3){ + toolsoftwareinfo.tool_version = std::to_string(tool_software_info); + } + if(controller_version==4){ + toolsoftwareinfo.tool_version = end_v.version; + } + toolsoftwareinfo.state = true; + this->Get_Tool_Software_Version_Result->publish(toolsoftwareinfo); + } + else + { + toolsoftwareinfo.state = false; + this->Get_Tool_Software_Version_Result->publish(toolsoftwareinfo); + RCLCPP_INFO (this->get_logger(),"The tool software error code is %d\n",res); + } +} +void RmArm::Get_Trajectory_File_List_Callback(const rm_ros_interfaces::msg::Gettrajectorylist::SharedPtr msg) //查询轨迹列表 +{ + int32_t res; + rm_trajectory_list_t trajectory_file_list; + rm_ros_interfaces::msg::Trajectorylist get_trajectory_file_list; + + rm_ros_interfaces::msg::Trajectoryinfo tral_info; + // copy = msg; + int page_num,page_size; + const char *vague_search=msg->vague_search.c_str(); + page_num = msg->page_num; + page_size = msg->page_size; + res = Rm_Api.rm_get_trajectory_file_list(robot_handle, page_num,page_size,vague_search,&trajectory_file_list); + if(res == 0) + { + get_trajectory_file_list.page_num = trajectory_file_list.page_num; + get_trajectory_file_list.page_size = trajectory_file_list.page_size; + get_trajectory_file_list.total_size = trajectory_file_list.total_size; + get_trajectory_file_list.vague_search = trajectory_file_list.vague_search; + for(int i=0;iGet_Trajectory_File_List_Result->publish(get_trajectory_file_list); + } + else + { + get_trajectory_file_list.state = false; + this->Get_Trajectory_File_List_Result->publish(get_trajectory_file_list); + RCLCPP_INFO (this->get_logger(),"The get_trajectory_file error code is %d\n",res); + } +} +void RmArm::Set_Run_Trajectory_Callback(const std_msgs::msg::String::SharedPtr msg) //开始运行指定轨迹 +{ + int32_t res; + std_msgs::msg::Bool set_run_trajectory_result; + const char *trajectory_name=msg->data.c_str(); + res = Rm_Api.rm_set_run_trajectory(robot_handle, trajectory_name); + if(res == 0) + { + set_run_trajectory_result.data = true; + this->Set_Run_Trajectory_Result->publish(set_run_trajectory_result); + } + else + { + set_run_trajectory_result.data = false; + this->Set_Run_Trajectory_Result->publish(set_run_trajectory_result); + RCLCPP_INFO (this->get_logger(),"Set_Run_Trajectory error code is %d\n",res); + } +} +void RmArm::Delete_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg) //删除指定轨迹 +{ + int32_t res; + std_msgs::msg::Bool Delete_Trajectory_File_result; + const char *trajectory_name=msg->data.c_str(); + res = Rm_Api.rm_delete_trajectory_file(robot_handle, trajectory_name); + if(res == 0) + { + Delete_Trajectory_File_result.data = true; + this->Delete_Trajectory_File_Result->publish(Delete_Trajectory_File_result); + } + else + { + Delete_Trajectory_File_result.data = false; + this->Delete_Trajectory_File_Result->publish(Delete_Trajectory_File_result); + RCLCPP_INFO (this->get_logger(),"Set_Run_Trajectory error code is %d\n",res); + } +} +void RmArm::Save_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg) //保存轨迹到控制机器 +{ + int32_t res; + std_msgs::msg::Bool Save_Trajectory_File_result; + const char *trajectory_name=msg->data.c_str(); + res = Rm_Api.rm_save_trajectory_file(robot_handle, trajectory_name); + if(res == 0) + { + Save_Trajectory_File_result.data = true; + this->Save_Trajectory_File_Result->publish(Save_Trajectory_File_result); + } + else + { + Save_Trajectory_File_result.data = false; + this->Save_Trajectory_File_Result->publish(Save_Trajectory_File_result); + RCLCPP_INFO (this->get_logger(),"Save_Trajectory_File error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Flowchart_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg)// 不支持三代控制器 +{ + int32_t res; + rm_ros_interfaces::msg::Flowchartrunstate flowchatrunstate; + rm_flowchart_run_state_t flow_run_state; + copy = msg; + res = Rm_Api.rm_get_flowchart_program_run_state(robot_handle, &flow_run_state); + if(res == 0) + { + flowchatrunstate.run_state = flow_run_state.run_state; + flowchatrunstate.id = flow_run_state.id; + flowchatrunstate.name = flow_run_state.name; + flowchatrunstate.plan_speed = flow_run_state.plan_speed; + flowchatrunstate.step_mode = flow_run_state.step_mode; + flowchatrunstate.modal_id = flow_run_state.modal_id; + flowchatrunstate.state = true; + this->Get_Flowchart_Program_Run_State_Result->publish(flowchatrunstate); + } + else + { + flowchatrunstate.state = false; + this->Get_Flowchart_Program_Run_State_Result->publish(flowchatrunstate); + RCLCPP_INFO (this->get_logger(),"The flow chat run error code is %d\n",res); + } +} + + +// ------------------------------------------Modbus相关------------------------------------------ +void RmArm::Add_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterinfo::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_master_info_t master; + std_msgs::msg::Bool Add_Modbus_Tcp_Master; + strcpy(master.master_name, msg->master_name.c_str()); + strcpy(master.ip, msg->ip.c_str()); + master.port = msg->port; + + res = Rm_Api.rm_add_modbus_tcp_master(robot_handle, master); + + if(res == 0) + { + Add_Modbus_Tcp_Master.data = true; + this->Add_Modbus_Tcp_Master_Result->publish(Add_Modbus_Tcp_Master); + } + else + { + Add_Modbus_Tcp_Master.data = false; + this->Add_Modbus_Tcp_Master_Result->publish(Add_Modbus_Tcp_Master); + RCLCPP_INFO (this->get_logger(),"The Add_Modbus_Tcp error code is %d\n",res); + } +} + +void RmArm::Update_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterupdata::SharedPtr msg) +{ + int32_t res; + rm_modbus_tcp_master_info_t master; + // copy = msg; + std_msgs::msg::Bool Update_Modbus_Tcp_Master_result; + char *old_master_name = (char*)malloc(14*sizeof(char)); + strcpy(old_master_name, msg->master_name.c_str()); + strcpy(master.master_name, msg->new_master_name.c_str()); + strcpy(master.ip, msg->ip.c_str()); + master.port = msg->port; + + res = Rm_Api.rm_update_modbus_tcp_master(robot_handle, old_master_name,master); + + if(res == 0) + { + Update_Modbus_Tcp_Master_result.data = true; + this->Update_Modbus_Tcp_Master_Result->publish(Update_Modbus_Tcp_Master_result); + } + else + { + Update_Modbus_Tcp_Master_result.data = false; + this->Update_Modbus_Tcp_Master_Result->publish(Update_Modbus_Tcp_Master_result); + RCLCPP_INFO (this->get_logger(),"The error code is %d\n",res); + } +} + +void RmArm::Delete_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg) +{ + int32_t res; + char master_name[20]; + std_msgs::msg::Bool Delete_Modbus_Tcp_Master_result; + strcpy(master_name, msg->master_name.c_str()); + + res = Rm_Api.rm_delete_modbus_tcp_master(robot_handle, master_name); + + if(res == 0) + { + Delete_Modbus_Tcp_Master_result.data = true; + this->Delete_Modbus_Tcp_Master_Result->publish(Delete_Modbus_Tcp_Master_result); + } + else + { + Delete_Modbus_Tcp_Master_result.data = false; + this->Delete_Modbus_Tcp_Master_Result->publish(Delete_Modbus_Tcp_Master_result); + RCLCPP_INFO (this->get_logger(),"The Delete_Modbus_Tcp_Master error code is %d\n",res); + } +} + +void RmArm::Get_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg) +{ + int32_t res; + rm_modbus_tcp_master_info_t master; + rm_ros_interfaces::msg::Modbustcpmasterinfo get_Tcp_Master_info; + // copy = msg; + char master_name[20]; + strcpy(master_name, msg->master_name.c_str()); + + res = Rm_Api.rm_get_modbus_tcp_master(robot_handle, master_name,&master); + + + if(res == 0) + { + get_Tcp_Master_info.ip = master.ip; + get_Tcp_Master_info.master_name = master.master_name; + get_Tcp_Master_info.port = master.port; + get_Tcp_Master_info.state = true; + this->Get_Modbus_Tcp_Master_Result->publish(get_Tcp_Master_info); + } + else + { + get_Tcp_Master_info.state = false; + this->Get_Modbus_Tcp_Master_Result->publish(get_Tcp_Master_info); + RCLCPP_INFO (this->get_logger(),"The get_Tcp_Master error code is %d\n",res); + } +} + +void RmArm::Get_Modbus_Tcp_Master_List_Callback(const rm_ros_interfaces::msg::Getmodbustcpmasterlist::SharedPtr msg) +{ + int32_t res; + rm_modbus_tcp_master_list_t master_list; + rm_ros_interfaces::msg::Modbustcpmasterlist get_Tcp_Master_list; + rm_ros_interfaces::msg::Modbustcpmasterinfo master_info; + // copy = msg; + int page_num,page_size; + char vague_search[20]; + page_num = msg->page_num; + page_size = msg->page_size; + strcpy(vague_search, msg->vague_search.c_str()); + + res = Rm_Api.rm_get_modbus_tcp_master_list(robot_handle, page_num,page_size,vague_search,&master_list); + + if(res == 0) + { + get_Tcp_Master_list.page_num = master_list.page_num; + get_Tcp_Master_list.page_size = master_list.page_size; + get_Tcp_Master_list.total_size = master_list.total_size; + get_Tcp_Master_list.vague_search = master_list.vague_search; + for(int i=0;iGet_Modbus_Tcp_Master_List_Result->publish(get_Tcp_Master_list); + } + else + { + get_Tcp_Master_list.state = false; + this->Get_Modbus_Tcp_Master_List_Result->publish(get_Tcp_Master_list); + RCLCPP_INFO (this->get_logger(),"The get_Tcp_Master_list error code is %d\n",res); + } +} + +void RmArm::Set_Controller_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg) +{ + int32_t res; + // copy = msg; + int tool_rs485_mode,baudrate; + std_msgs::msg::Bool controller_RS485_mode_set_result; + tool_rs485_mode = msg->mode; + baudrate = msg->baudrate; + + res = Rm_Api.rm_set_controller_rs485_mode(robot_handle, tool_rs485_mode, baudrate); + + if(res == 0) + { + controller_RS485_mode_set_result.data = true; + this->Set_Controller_RS485_Mode_Result->publish(controller_RS485_mode_set_result); + } + else + { + controller_RS485_mode_set_result.data = false; + this->Set_Controller_RS485_Mode_Result->publish(controller_RS485_mode_set_result); + RCLCPP_INFO (this->get_logger(),"The set_controller_rs485 error code is %d\n",res); + } +} + +void RmArm::Get_Controller_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + int tool_rs485_mode, baudrate; + rm_ros_interfaces::msg::RS485params controller_rs485_mode_get_result; + copy = msg; + + res = Rm_Api.rm_get_controller_rs485_mode_v4(robot_handle, &tool_rs485_mode, &baudrate); + + if(res == 0) + { + controller_rs485_mode_get_result.mode = tool_rs485_mode; + controller_rs485_mode_get_result.baudrate = baudrate; + controller_rs485_mode_get_result.state = true; + this->Get_Controller_RS485_Mode_v4_Result->publish(controller_rs485_mode_get_result); + } + else + { + controller_rs485_mode_get_result.state = false; + this->Get_Controller_RS485_Mode_v4_Result->publish(controller_rs485_mode_get_result); + RCLCPP_INFO (this->get_logger(),"The get_controller_rs485_mode_v4 error code is %d\n",res); + } +} +void RmArm::Set_Tool_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg) +{ + int32_t res; + // copy = msg; + int tool_rs485_mode,baudrate; + std_msgs::msg::Bool tool_RS485_mode_set_result; + tool_rs485_mode = msg->mode; + baudrate = msg->baudrate; + + res = Rm_Api.rm_set_tool_rs485_mode(robot_handle, tool_rs485_mode, baudrate); + + if(res == 0) + { + tool_RS485_mode_set_result.data = true; + this->Set_Tool_RS485_Mode_Result->publish(tool_RS485_mode_set_result); + } + else + { + tool_RS485_mode_set_result.data = false; + this->Set_Tool_RS485_Mode_Result->publish(tool_RS485_mode_set_result); + RCLCPP_INFO (this->get_logger(),"The set_tool_rs485_mode error code is %d\n",res); + } +} +void RmArm::Get_Tool_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + int tool_rs485_mode = 0; + int baudrate = 0; + rm_ros_interfaces::msg::RS485params tool_rs485_mode_get_result; + copy = msg; + res = Rm_Api.rm_get_tool_rs485_mode_v4(robot_handle, &tool_rs485_mode, &baudrate); + + if(res == 0) + { + tool_rs485_mode_get_result.mode = tool_rs485_mode; + tool_rs485_mode_get_result.baudrate = baudrate; + tool_rs485_mode_get_result.state = true; + this->Get_Tool_RS485_Mode_v4_Result->publish(tool_rs485_mode_get_result); + } + else + { + tool_rs485_mode_get_result.state = false; + this->Get_Tool_RS485_Mode_v4_Result->publish(tool_rs485_mode_get_result); + RCLCPP_INFO (this->get_logger(),"The get_tool_rs485_mode_v4 error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata read_coil_data; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_rtu_coils num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_rtu_coils(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_RTU_Coils_Result->publish(read_coil_data); + } + else + { + read_coil_data.state = false; + this->Read_Modbus_RTU_Coils_Result->publish(read_coil_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_rtu_coils error code is %d\n",res); + } +} +void RmArm::Write_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_write_params_t param; + std_msgs::msg::Bool write_coil_data_result; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + if((param.num == int(msg->data.size()))&&(param.num<=100)) + { + for(int i=0;idata[i]; + } + } + else if(msg->data.size()<=100) + { + param.num = msg->data.size(); + for(int i=0;idata[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_rtu_coils num is diff with data size use data size %d\n",param.num); + } + else if(msg->data.size()>100) + { + param.num = 100; + for(int i=0;i<100;i++) + { + param.data[i] = msg->data[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_rtu_coils num is over 100 use 100\n"); + } + + res = Rm_Api.rm_write_modbus_rtu_coils(robot_handle, param); + + if(res == 0) + { + write_coil_data_result.data = true; + this->Write_Modbus_RTU_Coils_Result->publish(write_coil_data_result); + } + else + { + write_coil_data_result.data = false; + this->Write_Modbus_RTU_Coils_Result->publish(write_coil_data_result); + RCLCPP_INFO (this->get_logger(),"The write_modbus_rtu_coils error code is %d\n",res); + } +} + + +void RmArm::Read_Modbus_RTU_Input_Status_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata read_input_status_data; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_rtu_input_status num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_rtu_input_status(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_RTU_Input_Status_Result->publish(read_input_status_data); + } + else + { + read_input_status_data.state = false; + this->Read_Modbus_RTU_Input_Status_Result->publish(read_input_status_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_rtu_input error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_RTU_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata read_holding_registers_data; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_rtu_holding_registers num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_rtu_holding_registers(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_RTU_Holding_Registers_Result->publish(read_holding_registers_data); + } + else + { + read_holding_registers_data.state = false; + this->Read_Modbus_RTU_Holding_Registers_Result->publish(read_holding_registers_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_rtu_holding error code is %d\n",res); + } +} + +void RmArm::Write_Modbus_RTU_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_write_params_t param; + std_msgs::msg::Bool write_Registers_data_result; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + // for(int i=0;idata[i]; + // } + if((param.num == int(msg->data.size()))&&(param.num<=100)) + { + for(int i=0;idata[i]; + } + } + else if(msg->data.size()<=100) + { + param.num = msg->data.size(); + for(int i=0;idata[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_rtu_registers num is diff with data size use data size %d\n",param.num); + } + else if(msg->data.size()>100) + { + param.num = 100; + for(int i=0;i<100;i++) + { + param.data[i] = msg->data[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_rtu_registers num is over 100 use 100\n"); + } + + res = Rm_Api.rm_write_modbus_rtu_registers(robot_handle, param); + + if(res == 0) + { + write_Registers_data_result.data = true; + this->Write_Modbus_RTU_Registers_Result->publish(write_Registers_data_result); + } + else + { + write_Registers_data_result.data = false; + this->Write_Modbus_RTU_Registers_Result->publish(write_Registers_data_result); + RCLCPP_INFO (this->get_logger(),"The write_modbus_rtu_registers error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_RTU_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_rtu_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata read_input_registers_data; + param.address = msg->address; + param.device = msg->device; + param.type = msg->type; + param.num = msg->num; + + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_rtu_input_registers num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_rtu_input_registers(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_RTU_Input_Registers_Result->publish(read_input_registers_data); + } + else + { + read_input_registers_data.state = false; + this->Read_Modbus_RTU_Input_Registers_Result->publish(read_input_registers_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_rtu_input_registers error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata tcp_read_coil_data; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_tcp_coils num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_tcp_coils(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_TCP_Coils_Result->publish(tcp_read_coil_data); + } + else + { + tcp_read_coil_data.state = false; + this->Read_Modbus_TCP_Coils_Result->publish(tcp_read_coil_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_tcp_coils error code is %d\n",res); + } +} +void RmArm::Write_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg) +{ + int32_t res; + rm_modbus_tcp_write_params_t param; + std_msgs::msg::Bool tcp_write_coil_data_result; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + // for(int i=0;idata[i]; + // } + if((param.num == int(msg->data.size()))&&(param.num<=100)) + { + for(int i=0;idata[i]; + } + } + else if(msg->data.size()<=100) + { + param.num = msg->data.size(); + for(int i=0;idata[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_tcp_coils num is diff with data size use data size %d\n",param.num); + } + else if(msg->data.size()>100) + { + param.num = 100; + for(int i=0;i<100;i++) + { + param.data[i] = msg->data[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_tcp_coils num is over 100 use 100\n"); + } + + res = Rm_Api.rm_write_modbus_tcp_coils(robot_handle, param); + + if(res == 0) + { + tcp_write_coil_data_result.data = true; + this->Write_Modbus_TCP_Coils_Result->publish(tcp_write_coil_data_result); + } + else + { + tcp_write_coil_data_result.data = false; + this->Write_Modbus_TCP_Coils_Result->publish(tcp_write_coil_data_result); + RCLCPP_INFO (this->get_logger(),"The write_modbus_tcp_coils error code is %d\n",res); + } +} + + +void RmArm::Read_Modbus_TCP_Input_Status_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata tcp_read_input_status_data; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_tcp_input_status num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_tcp_input_status(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_TCP_Input_Status_Result->publish(tcp_read_input_status_data); + } + else + { + tcp_read_input_status_data.state = false; + this->Read_Modbus_TCP_Input_Status_Result->publish(tcp_read_input_status_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_tcp_input_status error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_TCP_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata tcp_read_holding_registers_data; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_tcp_holding_registers num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_tcp_holding_registers(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_TCP_Holding_Registers_Result->publish(tcp_read_holding_registers_data); + } + else + { + tcp_read_holding_registers_data.state = false; + this->Read_Modbus_TCP_Holding_Registers_Result->publish(tcp_read_holding_registers_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_tcp_holding_registers error code is %d\n",res); + } +} + +void RmArm::Write_Modbus_TCP_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_write_params_t param; + std_msgs::msg::Bool tcp_write_TCP_registers_data_result; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + // for(int i=0;idata[i]; + // } + if((param.num == int(msg->data.size()))&&(param.num<=100)) + { + for(int i=0;idata[i]; + } + } + else if(msg->data.size()<=100) + { + param.num = msg->data.size(); + for(int i=0;idata[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_tcp_registers num is diff with data size use data size %d\n",param.num); + } + else if(msg->data.size()>100) + { + param.num = 100; + for(int i=0;i<100;i++) + { + param.data[i] = msg->data[i]; + } + RCLCPP_WARN (this->get_logger(),"The write_modbus_tcp_registers num is over 100 use 100\n"); + } + + res = Rm_Api.rm_write_modbus_tcp_registers(robot_handle, param); + + if(res == 0) + { + tcp_write_TCP_registers_data_result.data = true; + this->Write_Modbus_TCP_Registers_Result->publish(tcp_write_TCP_registers_data_result); + } + else + { + tcp_write_TCP_registers_data_result.data = false; + this->Write_Modbus_TCP_Registers_Result->publish(tcp_write_TCP_registers_data_result); + RCLCPP_INFO (this->get_logger(),"The write_modbus_tcp_registers error code is %d\n",res); + } +} + +void RmArm::Read_Modbus_TCP_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg) +{ + int32_t res; + // copy = msg; + rm_modbus_tcp_read_params_t param; + rm_ros_interfaces::msg::Modbusreaddata tcp_read_input_registers_data; + param.address = msg->address; + strcpy(param.master_name, msg->master_name.c_str()); + strcpy(param.ip, msg->ip.c_str()); + param.port = msg->port; + param.num = msg->num; + int data[100]; // 要读的数据的数量,数据长度不超过100 + if(param.num>100) + { + param.num = 100; + RCLCPP_WARN (this->get_logger(),"The read_modbus_tcp_input_registers num is over 100 use 100\n"); + } + res = Rm_Api.rm_read_modbus_tcp_input_registers(robot_handle, param, data); + + if(res == 0) + { + for(int i=0;iRead_Modbus_TCP_Input_Registers_Result->publish(tcp_read_input_registers_data); + } + else + { + tcp_read_input_registers_data.state = false; + this->Read_Modbus_TCP_Input_Registers_Result->publish(tcp_read_input_registers_data); + RCLCPP_INFO (this->get_logger(),"The read_modbus_tcp_input_registers error code is %d\n",res); + } +} + +// ------------------------------------------Modbus相关 end------------------------------------------ +void RmArm::Send_Project_Callback(const rm_ros_interfaces::msg::Sendproject::SharedPtr msg) //文件下发 +{ + int32_t res; + std_msgs::msg::Bool Send_Project_result; + rm_send_project_t project; + int errline; + strcpy(project.project_path,msg->project_path.c_str()); + project.project_path_len = msg->project_path_len; + project.plan_speed = msg->plan_speed; + project.only_save = msg->only_save; + project.save_id = msg->save_id; + project.step_flag = msg->step_flag; + project.auto_start = msg->auto_start; + project.project_type = msg->project_type; + res = Rm_Api.rm_send_project(robot_handle, project, &errline); + if(res == 0) + { + Send_Project_result.data = true; + this->Send_Project_Result->publish(Send_Project_result); + } + else + { + Send_Project_result.data = false; + this->Send_Project_Result->publish(Send_Project_result); + RCLCPP_INFO (this->get_logger(),"The error code is %d\n",res); + if(res == 1){ + if(errline ==0) + RCLCPP_INFO (this->get_logger(),"The rm_send_project length of the verification data is incorrect"); + else if(errline == -1) + { + RCLCPP_INFO (this->get_logger(),"rm_send_project no error"); + }else{ + RCLCPP_INFO (this->get_logger(),"The rm_send_project number of problematic engineering lines:%d",errline); + } + } + + } +} +void RmArm::Get_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg) //查询在线编程运行状态 +{ + int32_t res; + copy = msg; + rm_program_run_state_t run_state; + rm_ros_interfaces::msg::Programrunstate get_program_run_state_result; + res = Rm_Api.rm_get_program_run_state(robot_handle,&run_state); + if(res == 0) + { + get_program_run_state_result.run_state = run_state.run_state; + get_program_run_state_result.id = run_state.id; + get_program_run_state_result.edit_id = run_state.edit_id; + get_program_run_state_result.plan_num = run_state.plan_num; + get_program_run_state_result.total_loop = run_state.total_loop; + get_program_run_state_result.step_mode = run_state.step_mode; + get_program_run_state_result.plan_speed = run_state.plan_speed; + for(int i=0;iGet_Program_Run_State_Result->publish(get_program_run_state_result); + } + else + { + get_program_run_state_result.state = false; + this->Get_Program_Run_State_Result->publish(get_program_run_state_result); + RCLCPP_INFO (this->get_logger(),"Get_Program_Run_State error code is %d\n",res); + } +} + + +void RmArm::Arm_Start_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + + int32_t res; + std_msgs::msg::Bool arm_start_force_result; + copy = msg; + // res = Rm_Api.Service_Start_Force_Position_Move(m_sockhand, true); + res = Rm_Api.rm_start_force_position_move(robot_handle); + if(res == 0) + { + arm_start_force_result.data = true; + this->Start_Force_Position_Move_Result->publish(arm_start_force_result); + } + else + { + arm_start_force_result.data = false; + this->Start_Force_Position_Move_Result->publish(arm_start_force_result); + } +} + +void RmArm::Arm_Stop_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + int32_t res; + std_msgs::msg::Bool arm_stop_force_result; + copy = msg; + // res = Rm_Api.Service_Stop_Force_Position_Move(m_sockhand, true); + res = Rm_Api.rm_stop_force_position_move(robot_handle); + if(res == 0) + { + arm_stop_force_result.data = true; + this->Stop_Force_Position_Move_Result->publish(arm_stop_force_result); + } + else + { + arm_stop_force_result.data = false; + this->Stop_Force_Position_Move_Result->publish(arm_stop_force_result); + } +} + +void RmArm::Arm_Force_Position_Move_Joint_Callback(const rm_ros_interfaces::msg::Forcepositionmovejoint::SharedPtr msg) +{ + int32_t res; + float joint[7]; + int sensor; + int mode; + std_msgs::msg::Bool force_position_move_joint_result; + int dir; + float force; + bool follow; + for(int i = 0;i<6;i++) + { + joint[i] = msg->joint[i] * RAD_DEGREE; + } + if(msg->dof == 7) + { + joint[6] = msg->joint[6] * RAD_DEGREE; + } + + sensor = msg->sensor; + mode = msg->mode; + dir = msg->dir; + force = msg->force; + follow = msg->follow; + // res = Rm_Api.Service_Force_Position_Move_Joint(m_sockhand, joint, sensor, mode, dir, force, follow); + res = Rm_Api.rm_force_position_move_joint(robot_handle, joint, sensor, mode, dir, force, follow); + if(res != 0) + { + RCLCPP_INFO (this->get_logger(),"Arm force position move joint error code is %d\n",res); + } +} + +// void RmArm::Arm_Force_Position_Move_Joint_75_Callback(const rm_ros_interfaces::msg::Forcepositionmovejoint75::SharedPtr msg) +// { +// int32_t res; +// float joint[7]; +// byte sensor; +// byte mode; +// std_msgs::msg::Bool force_position_move_joint_result; +// int dir; +// float force; +// bool follow; +// for(int i = 0;i<7;i++) +// { +// joint[i] = msg->joint[i] * RAD_DEGREE; +// } +// sensor = msg->sensor; +// mode = msg->mode; +// dir = msg->dir; +// force = msg->force; +// follow = msg->follow; +// res = Rm_Api.Service_Force_Position_Move_Joint(m_sockhand, joint, sensor, mode, dir, force, follow); +// if(res != 0) +// { +// RCLCPP_INFO (this->get_logger(),"Arm force position move joint error code is %d\n",res); +// } +// } + +void RmArm::Arm_Force_Position_Move_Pose_Callback(const rm_ros_interfaces::msg::Forcepositionmovepose::SharedPtr msg) +{ + int32_t res; + rm_pose_t joint_pose; + int sensor; + int mode; + rm_quat_t qua; + rm_euler_t euler; + int dir; + float force; + bool follow; + qua.w = msg->pose.orientation.w; + qua.x = msg->pose.orientation.x; + qua.y = msg->pose.orientation.y; + qua.z = msg->pose.orientation.z; + // euler = Rm_Api.Service_Algo_Quaternion2Euler(qua); + euler = Rm_Api.rm_algo_quaternion2euler(qua); + joint_pose.position.x = msg->pose.position.x; + joint_pose.position.y = msg->pose.position.y; + joint_pose.position.z = msg->pose.position.z; + joint_pose.euler.rx = euler.rx; + joint_pose.euler.ry = euler.ry; + joint_pose.euler.rz = euler.rz; + sensor = msg->sensor; + mode = msg->mode; + dir = msg->dir; + force = msg->force; + follow = msg->follow; + // res = Rm_Api.Service_Force_Position_Move_Pose(m_sockhand, joint_pose, sensor, mode, dir, force, follow); + res = Rm_Api.rm_force_position_move_pose(robot_handle, joint_pose, sensor, mode, dir, force, follow); + if(res != 0) + { + RCLCPP_INFO (this->get_logger(),"Arm force position move pose error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Force_Postion_Callback(const rm_ros_interfaces::msg::Setforceposition::SharedPtr msg) +{ + int32_t res; + std_msgs::msg::Bool arm_set_force_postion_result; + int sensor; + int mode; + int direction; + int N; + // bool block; + sensor = msg->sensor; + mode = msg->mode; + direction = msg->direction; + N = msg->n; + // block = msg->block; + // res = Rm_Api.Service_Set_Force_Postion(m_sockhand, sensor, mode, direction, N, block); + res = Rm_Api.rm_set_force_position(robot_handle, sensor, mode, direction, N); + if(res == 0) + { + arm_set_force_postion_result.data = true; + this->Set_Force_Postion_Result->publish(arm_set_force_postion_result); + } + else + { + arm_set_force_postion_result.data = false; + this->Set_Force_Postion_Result->publish(arm_set_force_postion_result); + RCLCPP_INFO (this->get_logger(),"Arm_set_force_postion_callback error code is %d\n",res); + } +} +void RmArm::Arm_Stop_Force_Postion_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + copy = msg; + int32_t res; + std_msgs::msg::Bool arm_stop_force_postion_result; + // bool block; + // block = msg->data; + // res = Rm_Api.Service_Stop_Force_Postion(m_sockhand, block); + res = Rm_Api.rm_stop_force_position(robot_handle); + if(res == 0) + { + arm_stop_force_postion_result.data = true; + this->Stop_Force_Postion_Result->publish(arm_stop_force_postion_result); + } + else + { + arm_stop_force_postion_result.data = false; + this->Stop_Force_Postion_Result->publish(arm_stop_force_postion_result); + RCLCPP_INFO (this->get_logger(),"Arm stop force postion error code is %d\n",res); + } +} + +void RmArm::Arm_Change_Work_Frame_Callback(const std_msgs::msg::String::SharedPtr msg) +{ + //FRAME_NAME work_frame; + const char *work_name=msg->data.c_str(); + int32_t res; + std_msgs::msg::Bool arm_change_work_frame_result; + // strcpy(*work_name, msg->data.c_str()); + // res = Rm_Api.Service_Change_Work_Frame(m_sockhand, work_frame.name, RM_BLOCK); + res = Rm_Api.rm_change_work_frame(robot_handle, work_name); + if(res == 0) + { + arm_change_work_frame_result.data = true; + this->Change_Work_Frame_Result->publish(arm_change_work_frame_result); + } + else + { + arm_change_work_frame_result.data = false; + this->Change_Work_Frame_Result->publish(arm_change_work_frame_result); + RCLCPP_INFO(this->get_logger(),"Arm_change_work_frame_callback error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Curr_WorkFrame_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + //FRAME frame; + rm_frame_t work_frame; + int32_t res; + std_msgs::msg::String curr_frame; + std_msgs::msg::Bool arm_change_work_frame_result; + copy = msg; + // memset(frame.frame_name.name,'\0',sizeof(frame.frame_name.name)); + // res = Rm_Api.Service_Get_Current_Work_Frame(m_sockhand, &frame); + res = Rm_Api.rm_get_current_work_frame(robot_handle, &work_frame); + if(res == 0) + { + curr_frame.data = work_frame.frame_name; + this->Get_Curr_WorkFrame_Result->publish(curr_frame); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm_get_curr_workFrame_callback error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Current_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + //FRAME frame; + rm_frame_t tool_frame; + int32_t res; + std_msgs::msg::String curr_frame; + std_msgs::msg::Bool arm_change_work_frame_result; + copy = msg; + //memset(frame.frame_name.name,'\0',sizeof(frame.frame_name.name)); + // res = Rm_Api.Service_Get_Current_Tool_Frame(m_sockhand, &frame); + res = Rm_Api.rm_get_current_tool_frame(robot_handle, &tool_frame); + if(res == 0) + { + curr_frame.data = tool_frame.frame_name; + this->Get_Current_Tool_Frame_Result->publish(curr_frame); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm_get_curr_workFrame_callback error code is %d\n",res); + } +} + +void RmArm::Arm_Get_All_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + // FRAME_NAME name[10]; + rm_frame_name_t frame_names[10] = {0}; + int32_t res; + rm_ros_interfaces::msg::Getallframe all_tool_frame; + int len=-1; + copy = msg; + int i; + res = Rm_Api.rm_get_total_tool_frame(robot_handle, frame_names, &len); + if(res == 0 && len <= 10) + { + for(i = 0;iget_logger(),"Arm all tool frame is %s\n",frame_names[i].name); + all_tool_frame.frame_name[i] =std::string(frame_names[i].name); + } + for(i = len;i<10;i++) + { + all_tool_frame.frame_name[i] = ""; + } + this->Get_All_Tool_Frame_Result->publish(all_tool_frame); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm_get_all_tool_frame_callback error code is %d\n",res); + } +} + +void RmArm::Arm_Get_All_Work_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + // char name[10]; + rm_frame_name_t frame_names[10] = {0}; + int32_t res; + rm_ros_interfaces::msg::Getallframe all_work_frame; + int len=-1; + int i; + // for(i = 0;i<=9;i++) + // { + // memset(name[i].name,'\0',sizeof(name[i].name)); + // } + copy = msg; + // res = Rm_Api.Service_Get_All_Work_Frame(m_sockhand, name, &len); + res = Rm_Api.rm_get_total_work_frame(robot_handle, frame_names, &len); + if(res == 0 && len <= 10) + { + for(i = 0;i<=len;i++) + { + all_work_frame.frame_name[i] = std::string(frame_names[i].name); + } + for(i = len;i<10;i++) + { + all_work_frame.frame_name[i] = ""; + } + this->Get_All_Work_Frame_Result->publish(all_work_frame); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm_get_all_work_frame_callback error code is %d\n",res); + } +} + + +void RmArm::Arm_Set_Tool_Voltage_Callback(const std_msgs::msg::UInt16::SharedPtr msg) +{ + int type; + int32_t res; + std_msgs::msg::Bool arm_set_tool_voltage_result; + type = msg->data; + // res = Rm_Api.Service_Set_Tool_Voltage(m_sockhand, type, RM_BLOCK); + res = Rm_Api.rm_set_tool_voltage(robot_handle, type); + if(res == 0) + { + arm_set_tool_voltage_result.data = true; + this->Set_Tool_Voltage_Result->publish(arm_set_tool_voltage_result); + } + else + { + arm_set_tool_voltage_result.data = false; + this->Set_Tool_Voltage_Result->publish(arm_set_tool_voltage_result); + RCLCPP_INFO (this->get_logger(),"Arm set tool voltage error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Joint_Err_Clear_Callback(const rm_ros_interfaces::msg::Jointerrclear::SharedPtr msg) +{ + int joint_num; + // bool block; + int32_t res; + std_msgs::msg::Bool set_joint_err_clear_result; + joint_num = msg->joint_num; + // block = msg->block; + // res = Rm_Api.Service_Set_Joint_Err_Clear(m_sockhand, joint_num, block); + res = Rm_Api.rm_set_joint_clear_err(robot_handle, joint_num); + + if(res == 0) + { + set_joint_err_clear_result.data = true; + this->Set_Joint_Err_Clear_Result->publish(set_joint_err_clear_result); + } + else + { + set_joint_err_clear_result.data = false; + this->Set_Joint_Err_Clear_Result->publish(set_joint_err_clear_result); + RCLCPP_INFO (this->get_logger(),"Arm set joint err clear callback error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Gripper_Pick_On_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg) +{ + int speed; + int force; + bool block; + int timeout; + int32_t res; + std_msgs::msg::Bool set_gripper_pick_on_result; + speed = msg->speed; + force = msg->force; + block = msg->block; + timeout = msg->timeout; + // res = Rm_Api.Service_Set_Gripper_Pick_On(m_sockhand, speed, force, block, timeout); + res = Rm_Api.rm_set_gripper_pick_on(robot_handle, speed, force, block, timeout); + if(res == 0) + { + set_gripper_pick_on_result.data = true; + this->Set_Gripper_Pick_On_Result->publish(set_gripper_pick_on_result); + } + else + { + set_gripper_pick_on_result.data = false; + this->Set_Gripper_Pick_On_Result->publish(set_gripper_pick_on_result); + RCLCPP_INFO (this->get_logger(),"Arm set gripper pick on error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Gripper_Pick_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg) +{ + int speed; + int force; + bool block; + int timeout; + int32_t res; + std_msgs::msg::Bool set_gripper_pick_result; + speed = msg->speed; + force = msg->force; + block = msg->block; + timeout = msg->timeout; + // res = Rm_Api.Service_Set_Gripper_Pick(m_sockhand, speed, force, block, timeout); + res = Rm_Api.rm_set_gripper_pick(robot_handle, speed, force, block, timeout); + if(res == 0) + { + set_gripper_pick_result.data = true; + this->Set_Gripper_Pick_Result->publish(set_gripper_pick_result); + } + else + { + set_gripper_pick_result.data = false; + this->Set_Gripper_Pick_Result->publish(set_gripper_pick_result); + RCLCPP_INFO (this->get_logger(),"Arm set gripper pick error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Gripper_Position_Callback(const rm_ros_interfaces::msg::Gripperset::SharedPtr msg) +{ + int position; + bool block; + int timeout; + int32_t res; + std_msgs::msg::Bool set_gripper_position_result; + position = msg->position; + block = msg->block; + timeout = msg->timeout; + // res = Rm_Api.Service_Set_Gripper_Position(m_sockhand, position, block, timeout); + res = Rm_Api.rm_set_gripper_position(robot_handle, position, block, timeout); + if(res == 0) + { + set_gripper_position_result.data = true; + this->Set_Gripper_Position_Result->publish(set_gripper_position_result); + } + else + { + set_gripper_position_result.data = false; + this->Set_Gripper_Position_Result->publish(set_gripper_position_result); + RCLCPP_INFO (this->get_logger(),"Arm set gripper position error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Posture_Callback(const rm_ros_interfaces::msg::Handposture::SharedPtr msg) +{ + int posture_num; + bool block; + int timeout; + int32_t res; + std_msgs::msg::Bool set_hand_posture_result; + posture_num = msg->posture_num; + block = msg->block; + timeout = msg->timeout; + // res = Rm_Api.Service_Set_Hand_Posture(m_sockhand, posture_num, block); + res = Rm_Api.rm_set_hand_posture(robot_handle, posture_num, block, timeout); + if(res == 0) + { + set_hand_posture_result.data = true; + this->Set_Hand_Posture_Result->publish(set_hand_posture_result); + } + else + { + set_hand_posture_result.data = false; + this->Set_Hand_Posture_Result->publish(set_hand_posture_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand posture error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Seq_Callback(const rm_ros_interfaces::msg::Handseq::SharedPtr msg) +{ + int seq_num; + bool block; + int timeout; + int32_t res; + std_msgs::msg::Bool set_hand_seq_result; + seq_num = msg->seq_num; + block = msg->block; + timeout = msg->timeout; + // res = Rm_Api.Service_Set_Hand_Seq(m_sockhand, seq_num, block); + res = Rm_Api.rm_set_hand_seq(robot_handle, seq_num, block, timeout); + if(res == 0) + { + set_hand_seq_result.data = true; + this->Set_Hand_Seq_Result->publish(set_hand_seq_result); + } + else + { + set_hand_seq_result.data = false; + this->Set_Hand_Seq_Result->publish(set_hand_seq_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand seq error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg) +{ + int angle[6]; + // bool block; + int32_t res; + std_msgs::msg::Bool set_hand_angle_result; + for(int i = 0;i<6;i++) + { + angle[i] = msg->hand_angle[i]; + } + // block = msg->block; + //res = Rm_Api.Service_Set_Hand_Angle(m_sockhand, angle, block); + res = Rm_Api.rm_set_hand_angle(robot_handle, angle); + + if(res == 0) + { + set_hand_angle_result.data = true; + this->Set_Hand_Angle_Result->publish(set_hand_angle_result); + } + else + { + set_hand_angle_result.data = false; + this->Set_Hand_Angle_Result->publish(set_hand_angle_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand angle error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Speed_Callback(const rm_ros_interfaces::msg::Handspeed::SharedPtr msg) +{ + int speed; + //bool block; + int32_t res; + std_msgs::msg::Bool set_hand_speed_result; + speed = msg->hand_speed; + // block = msg->block; + // res = Rm_Api.Service_Set_Hand_Speed(m_sockhand, speed, block); + res = Rm_Api.rm_set_hand_speed(robot_handle, speed); + if(res == 0) + { + set_hand_speed_result.data = true; + this->Set_Hand_Speed_Result->publish(set_hand_speed_result); + } + else + { + set_hand_speed_result.data = false; + this->Set_Hand_Speed_Result->publish(set_hand_speed_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand speed error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Force_Callback(const rm_ros_interfaces::msg::Handforce::SharedPtr msg) +{ + int force; + // bool block; + int32_t res; + std_msgs::msg::Bool set_hand_force_result; + force = msg->hand_force; + // block = msg->block; + // res = Rm_Api.Service_Set_Hand_Force(m_sockhand, force, block); + res = Rm_Api.rm_set_hand_force(robot_handle, force); + if(res == 0) + { + set_hand_force_result.data = true; + this->Set_Hand_Force_Result->publish(set_hand_force_result); + } + else + { + set_hand_force_result.data = false; + this->Set_Hand_Force_Result->publish(set_hand_force_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand force error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Follow_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg) +{ + int angle[6]; + int block; + int32_t res; + std_msgs::msg::Bool set_hand_angle_result; + for(int i = 0;i<6;i++) + { + angle[i] = msg->hand_angle[i]; + } + block = msg->block; + // res = Rm_Api.Service_Set_Hand_Follow_Angle(m_sockhand, angle, block); + res = Rm_Api.rm_set_hand_follow_angle(robot_handle, angle, block); + if(res == 0) + { + set_hand_angle_result.data = true; + this->Set_Hand_Follow_Angle_Result->publish(set_hand_angle_result); + } + else + { + set_hand_angle_result.data = false; + this->Set_Hand_Follow_Angle_Result->publish(set_hand_angle_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand follow angle error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Hand_Follow_Pos_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg) +{ + int pos[6]; + int block; + int32_t res; + std_msgs::msg::Bool set_hand_pos_result; + for(int i = 0;i<6;i++) + { + pos[i] = msg->hand_angle[i]; + } + block = msg->block; + // res = Rm_Api.Service_Set_Hand_Follow_Pos(m_sockhand, pos, block); + res = Rm_Api.rm_set_hand_follow_pos(robot_handle, pos, block); + if(res == 0) + { + set_hand_pos_result.data = true; + this->Set_Hand_Follow_Pos_Result->publish(set_hand_pos_result); + } + else + { + set_hand_pos_result.data = false; + this->Set_Hand_Follow_Pos_Result->publish(set_hand_pos_result); + RCLCPP_INFO (this->get_logger(),"Arm set hand follow angle error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Lift_Speed_Callback(const rm_ros_interfaces::msg::Liftspeed::SharedPtr msg) +{ + int speed; + int32_t res; + std_msgs::msg::Bool set_lift_speed_result; + speed = msg->speed; + // res = Rm_Api.Service_Set_Lift_Speed(m_sockhand, speed); + res = Rm_Api.rm_set_lift_speed(robot_handle, speed); + if(res == 0) + { + set_lift_speed_result.data = true; + this->Set_Lift_Speed_Result->publish(set_lift_speed_result); + } + else + { + set_lift_speed_result.data = false; + this->Set_Lift_Speed_Result->publish(set_lift_speed_result); + RCLCPP_INFO (this->get_logger(),"Arm set lift speed result error code is %d\n",res); + } +} + +void RmArm::Arm_Set_Lift_Height_Callback(const rm_ros_interfaces::msg::Liftheight::SharedPtr msg) +{ + int speed; + int height; + bool block; + int32_t res; + std_msgs::msg::Bool set_lift_height_result; + speed = msg->speed; + height = msg->height; + block = msg->block; + // res = Rm_Api.Service_Set_Lift_Height(m_sockhand, height, speed, block); + res = Rm_Api.rm_set_lift_height(robot_handle, speed, height, block); + if(res == 0) + { + set_lift_height_result.data = true; + this->Set_Lift_Height_Result->publish(set_lift_height_result); + } + else + { + set_lift_height_result.data = false; + this->Set_Lift_Height_Result->publish(set_lift_height_result); + RCLCPP_INFO (this->get_logger(),"Arm set lift height result error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Lift_State_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + // int current; + // int height; + // int err_flag; + // int mode; + int32_t res; + rm_ros_interfaces::msg::Liftstate lift_state; + rm_expand_state_t state; + copy = msg; + // res = Rm_Api.Service_Get_Lift_State(m_sockhand, &height, ¤t, &err_flag, &mode); + res = Rm_Api.rm_get_lift_state(robot_handle, &state); + if(res == 0) + { + lift_state.current = state.current; + lift_state.height = state.pos; + lift_state.err_flag = state.err_flag; + lift_state.mode = state.mode; + // lift_state.current = current; + // lift_state.height = height; + // lift_state.err_flag = err_flag; + // lift_state.mode = mode; + this->Get_Lift_State_Result->publish(lift_state); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm set lift state result error code is %d\n",res); + } +} + + +void RmArm::Arm_Get_Current_Arm_State_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + rm_pose_t pose; + // float joint[7]; + // u_int16_t Err; + // u_int8_t Err_len; + rm_current_arm_state_t current_state; + int32_t res; + copy = msg; + std_msgs::msg::Bool get_current_arm_State_result; + rm_euler_t euler; + rm_quat_t quat; + int i; + // res = Rm_Api.Service_Get_Current_Arm_State(m_sockhand, joint, &pose, &Err, &Err_len); + res = Rm_Api.rm_get_current_arm_state(robot_handle, ¤t_state); + if(res == 0) + { + pose = current_state.pose; + + Arm_original_state.dof = 6; + Arm_state.dof = 6; + for(i=0;i<6;i++) + { + Arm_original_state.joint[i] = current_state.joint[i]; + Arm_state.joint[i] = current_state.joint[i] * DEGREE_RAD; + } + if(arm_dof_g == 7) + { + Arm_original_state.joint[6] = current_state.joint[6]; + Arm_state.joint[6] = current_state.joint[6] * DEGREE_RAD; + Arm_original_state.dof = 7; + Arm_state.dof = 7; + } + + Arm_original_state.pose[0] = pose.position.x; + Arm_original_state.pose[1] = pose.position.y; + Arm_original_state.pose[2] = pose.position.z; + Arm_original_state.pose[3] = pose.euler.rx; + Arm_original_state.pose[4] = pose.euler.ry; + Arm_original_state.pose[5] = pose.euler.rz; + Arm_original_state.err = *current_state.err.err; + Arm_original_state.err_len = current_state.err.err_len; + this->Get_Current_Arm_Original_State_Result->publish(Arm_original_state); + + euler.rx = pose.euler.rx; + euler.ry = pose.euler.ry; + euler.rz = pose.euler.rz; + // quat = Rm_Api.Service_Algo_Euler2Quaternion(euler); + quat = Rm_Api.rm_algo_euler2quaternion(euler); + Arm_state.pose.orientation.w = quat.w; + Arm_state.pose.orientation.x = quat.x; + Arm_state.pose.orientation.y = quat.y; + Arm_state.pose.orientation.z = quat.z; + Arm_state.pose.position.x = pose.position.x; + Arm_state.pose.position.y = pose.position.y; + Arm_state.pose.position.z = pose.position.z; + Arm_state.err = *current_state.err.err; + Arm_state.err_len = current_state.err.err_len; + this->Get_Current_Arm_State_Result->publish(Arm_state); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm get current arm state error code is %d\n",res); + } +} + +void RmArm::Arm_Clear_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + copy = msg; + // bool block; + int32_t res; + std_msgs::msg::Bool clear_force_data_result; + // block = msg->data; + // res = Rm_Api.Service_Clear_Force_Data(m_sockhand, block); + res = Rm_Api.rm_clear_force_data(robot_handle); + + if(res == 0) + { + clear_force_data_result.data = true; + this->Clear_Force_Data_Result->publish(clear_force_data_result); + } + else + { + clear_force_data_result.data = false; + this->Clear_Force_Data_Result->publish(clear_force_data_result); + RCLCPP_INFO (this->get_logger(),"Arm clear force data error code is %d\n",res); + } +} + +void RmArm::Arm_Get_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg) +{ + rm_ros_interfaces::msg::Sixforce force; + rm_ros_interfaces::msg::Sixforce zero_force; + rm_ros_interfaces::msg::Sixforce work_zero; + rm_ros_interfaces::msg::Sixforce tool_zero; + // float force_data[6]; + // float zero_force_data[6]; + // float work_zero_data[6]; + // float tool_zero_data[6]; + rm_force_data_t data; + copy = msg; + int32_t res; + // res = Rm_Api.Service_Get_Force_Data(m_sockhand, force_data, zero_force_data, work_zero_data, tool_zero_data); + res = Rm_Api.rm_get_force_data(robot_handle, &data); + if(res == 0) + { + force.force_fx = data.force_data[0]; + force.force_fy = data.force_data[1]; + force.force_fz = data.force_data[2]; + force.force_mx = data.force_data[3]; + force.force_my = data.force_data[4]; + force.force_mz = data.force_data[5]; + Get_Force_Data_Result->publish(force); + zero_force.force_fx = data.zero_force_data[0]; + zero_force.force_fy = data.zero_force_data[1]; + zero_force.force_fz = data.zero_force_data[2]; + zero_force.force_mx = data.zero_force_data[3]; + zero_force.force_my = data.zero_force_data[4]; + zero_force.force_mz = data.zero_force_data[5]; + Get_Zero_Force_Result->publish(zero_force); + work_zero.force_fx = data.work_zero_force_data[0]; + work_zero.force_fy = data.work_zero_force_data[1]; + work_zero.force_fz = data.work_zero_force_data[2]; + work_zero.force_mx = data.work_zero_force_data[3]; + work_zero.force_my = data.work_zero_force_data[4]; + work_zero.force_mz = data.work_zero_force_data[5]; + Get_Work_Zero_Result->publish(work_zero); + tool_zero.force_fx = data.tool_zero_force_data[0]; + tool_zero.force_fy = data.tool_zero_force_data[1]; + tool_zero.force_fz = data.tool_zero_force_data[2]; + tool_zero.force_mx = data.tool_zero_force_data[3]; + tool_zero.force_my = data.tool_zero_force_data[4]; + tool_zero.force_mz = data.tool_zero_force_data[5]; + Get_Tool_Zero_Result->publish(tool_zero); + } + else + { + RCLCPP_INFO (this->get_logger(),"Arm get force data error code is %d\n",res); + } +} + +void Udp_Robot_Status_Callback(rm_realtime_arm_joint_state_t data) +{ + for(int i = 0; i < 6; i++) + { + Udp_RM_Joint.joint[i] = data.joint_status.joint_position[i]; + Udp_RM_Joint.err_flag[i] = data.joint_status.joint_err_code[i]; + Udp_RM_Joint.joint_current[i] = data.joint_status.joint_current[i]; + Udp_RM_Joint.en_flag[i] = data.joint_status.joint_en_flag[i]; + Udp_RM_Joint.joint_speed[i] = data.joint_status.joint_speed[i]; + Udp_RM_Joint.joint_temperature[i] = data.joint_status.joint_temperature[i]; + Udp_RM_Joint.joint_voltage[i] = data.joint_status.joint_voltage[i]; + } + if(arm_dof_g == 7) + { + Udp_RM_Joint.joint[6] = data.joint_status.joint_position[6]; + Udp_RM_Joint.err_flag[6] = data.joint_status.joint_err_code[6]; + Udp_RM_Joint.joint_current[6] = data.joint_status.joint_current[6]; + Udp_RM_Joint.en_flag[6] = data.joint_status.joint_en_flag[6]; + Udp_RM_Joint.joint_speed[6] = data.joint_status.joint_speed[6]; + Udp_RM_Joint.joint_temperature[6] = data.joint_status.joint_temperature[6]; + Udp_RM_Joint.joint_voltage[6] = data.joint_status.joint_voltage[6]; + } + if(Udp_RM_Joint.udp_rm_err.err_len != data.err.err_len) + { + Udp_RM_Joint.udp_rm_err.err_len = data.err.err_len; + Udp_RM_Joint.udp_rm_err.err.resize(Udp_RM_Joint.udp_rm_err.err_len); + for(int i = 0; iRm_Err_Result->publish(udp_rm_err_); + udp_real_joint_.header.stamp = this->now(); + this->Joint_Position_Result->publish(udp_real_joint_); + this->Joint_Error_Code_Result->publish(udp_joint_error_code_); + udp_arm_current_status_.arm_current_status = Udp_RM_Joint.arm_current_status; + //RCLCPP_INFO (this->get_logger(),"udp publisher arm_current_status is %d\n",udp_arm_current_status_.arm_current_status); + this->Arm_Current_Status_Result->publish(udp_arm_current_status_); + this->Joint_Current_Result->publish(udp_joint_current_); + this->Joint_En_Flag_Result->publish(udp_joint_en_flag_); + this->Joint_Speed_Result->publish(udp_joint_speed_); + this->Joint_Temperature_Result->publish(udp_joint_temperature_); + this->Joint_Voltage_Result->publish(udp_joint_voltage_); + udp_arm_pose_.position.x = Udp_RM_Joint.joint_position[0]; + udp_arm_pose_.position.y = Udp_RM_Joint.joint_position[1]; + udp_arm_pose_.position.z = Udp_RM_Joint.joint_position[2]; + udp_arm_pose_.orientation.w = Udp_RM_Joint.joint_quat[0]; + udp_arm_pose_.orientation.x = Udp_RM_Joint.joint_quat[1]; + udp_arm_pose_.orientation.y = Udp_RM_Joint.joint_quat[2]; + udp_arm_pose_.orientation.z = Udp_RM_Joint.joint_quat[3]; + this->Arm_Position_Result->publish(udp_arm_pose_); + udp_joint_pose_euler_.euler[0] = Udp_RM_Joint.joint_euler[0]; + udp_joint_pose_euler_.euler[1] = Udp_RM_Joint.joint_euler[1]; + udp_joint_pose_euler_.euler[2] = Udp_RM_Joint.joint_euler[2]; + udp_joint_pose_euler_.position[0]=Udp_RM_Joint.joint_position[0]; + udp_joint_pose_euler_.position[1]=Udp_RM_Joint.joint_position[1]; + udp_joint_pose_euler_.position[2]=Udp_RM_Joint.joint_position[2]; + this->Joint_Pose_Euler_Result->publish(udp_joint_pose_euler_); + // sys_err_.data = Udp_RM_Joint.sys_err; + // this->Sys_Err_Result->publish(sys_err_); + // arm_err_.data = Udp_RM_Joint.arm_err; + // this->Arm_Err_Result->publish(arm_err_); + arm_coordinate_.data = Udp_RM_Joint.coordinate; + this->Arm_Coordinate_Result->publish(arm_coordinate_); + if(udp_hand_g == true) + { + for(int i = 0;i<6;i++) + { + udp_hand_status_.hand_angle[i] = Udp_RM_Joint.hand_angle[i]; + udp_hand_status_.hand_force[i] = Udp_RM_Joint.hand_force[i]; + udp_hand_status_.hand_pos[i] = Udp_RM_Joint.hand_pos[i]; + udp_hand_status_.hand_state[i] = Udp_RM_Joint.hand_state[i]; + } + udp_hand_status_.hand_err = Udp_RM_Joint.hand_err; + this->Hand_Status_Result->publish(udp_hand_status_); + } + if(rm_plus_base_g == true) + { + for(int i = 0;i<10;i++) + { + udp_rm_plus_base_.pos_up[i] = Udp_RM_Joint.udp_rm_plus_base_info.pos_up[i]; + udp_rm_plus_base_.pos_low[i] = Udp_RM_Joint.udp_rm_plus_base_info.pos_low[i]; + udp_rm_plus_base_.speed_up[i] = Udp_RM_Joint.udp_rm_plus_base_info.speed_up[i]; + udp_rm_plus_base_.speed_low[i] = Udp_RM_Joint.udp_rm_plus_base_info.speed_low[i]; + udp_rm_plus_base_.force_up[i] = Udp_RM_Joint.udp_rm_plus_base_info.force_up[i]; + udp_rm_plus_base_.force_low[i] = Udp_RM_Joint.udp_rm_plus_base_info.force_low[i]; + } + for(int i = 0; i < 2; i++) + { + udp_rm_plus_base_.pos_up[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.pos_up[10+i]; + udp_rm_plus_base_.pos_low[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.pos_low[10+i]; + udp_rm_plus_base_.speed_up[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.speed_up[10+i]; + udp_rm_plus_base_.speed_low[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.speed_low[10+i]; + udp_rm_plus_base_.force_up[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.force_up[10+i]; + udp_rm_plus_base_.force_low[10+i] = Udp_RM_Joint.udp_rm_plus_base_info.force_low[10+i]; + } + udp_rm_plus_base_.manu = Udp_RM_Joint.udp_rm_plus_base_info.manu; + udp_rm_plus_base_.hv = Udp_RM_Joint.udp_rm_plus_base_info.hv; + udp_rm_plus_base_.sv = Udp_RM_Joint.udp_rm_plus_base_info.sv; + udp_rm_plus_base_.bv = Udp_RM_Joint.udp_rm_plus_base_info.bv; + + udp_rm_plus_base_.id = Udp_RM_Joint.udp_rm_plus_base_info.id; + udp_rm_plus_base_.dof = Udp_RM_Joint.udp_rm_plus_base_info.dof; + udp_rm_plus_base_.check = Udp_RM_Joint.udp_rm_plus_base_info.check; + udp_rm_plus_base_.bee = Udp_RM_Joint.udp_rm_plus_base_info.bee; + udp_rm_plus_base_.force = Udp_RM_Joint.udp_rm_plus_base_info.force; + udp_rm_plus_base_.touch = Udp_RM_Joint.udp_rm_plus_base_info.touch; + udp_rm_plus_base_.touch_num = Udp_RM_Joint.udp_rm_plus_base_info.touch_num; + udp_rm_plus_base_.touch_sw = Udp_RM_Joint.udp_rm_plus_base_info.touch_sw; + udp_rm_plus_base_.hand = Udp_RM_Joint.udp_rm_plus_base_info.hand; + this->Rm_Plus_Base_Result->publish(udp_rm_plus_base_); + } + if(rm_plus_state_g == true) + { + udp_rm_plus_state_.sys_state = Udp_RM_Joint.udp_rm_plus_state_info.sys_state; + for(int i = 0; i < 12; i++) + { + udp_rm_plus_state_.dof_state[i] = Udp_RM_Joint.udp_rm_plus_state_info.dof_state[i]; + udp_rm_plus_state_.dof_err[i] = Udp_RM_Joint.udp_rm_plus_state_info.dof_err[i]; + udp_rm_plus_state_.pos[i] = Udp_RM_Joint.udp_rm_plus_state_info.pos[i]; + udp_rm_plus_state_.speed[i] = Udp_RM_Joint.udp_rm_plus_state_info.speed[i]; + udp_rm_plus_state_.angle[i] = Udp_RM_Joint.udp_rm_plus_state_info.angle[i]; + udp_rm_plus_state_.current[i] = Udp_RM_Joint.udp_rm_plus_state_info.current[i]; + udp_rm_plus_state_.normal_force[i] = Udp_RM_Joint.udp_rm_plus_state_info.normal_force[i]; + udp_rm_plus_state_.tangential_force[i] = Udp_RM_Joint.udp_rm_plus_state_info.tangential_force[i]; + udp_rm_plus_state_.tangential_force_dir[i] = Udp_RM_Joint.udp_rm_plus_state_info.tangential_force_dir[i]; + udp_rm_plus_state_.tsa[i] = Udp_RM_Joint.udp_rm_plus_state_info.tsa[i]; + udp_rm_plus_state_.tma[i] = Udp_RM_Joint.udp_rm_plus_state_info.tma[i]; + udp_rm_plus_state_.touch_data[i] = Udp_RM_Joint.udp_rm_plus_state_info.touch_data[i]; + udp_rm_plus_state_.force[i] = Udp_RM_Joint.udp_rm_plus_state_info.force[i]; + } + for(int i = 12; i < 18; i++) + { + udp_rm_plus_state_.normal_force[i] = Udp_RM_Joint.udp_rm_plus_state_info.normal_force[i]; + udp_rm_plus_state_.tangential_force[i] = Udp_RM_Joint.udp_rm_plus_state_info.tangential_force[i]; + udp_rm_plus_state_.tangential_force_dir[i] = Udp_RM_Joint.udp_rm_plus_state_info.tangential_force_dir[i]; + udp_rm_plus_state_.touch_data[i] = Udp_RM_Joint.udp_rm_plus_state_info.touch_data[i]; + } + this->Rm_Plus_State_Result->publish(udp_rm_plus_state_); + } + if(Udp_RM_Joint.control_version == 2) + { + udp_sixforce_.force_fx = Udp_RM_Joint.six_force[0]; + udp_sixforce_.force_fy = Udp_RM_Joint.six_force[1]; + udp_sixforce_.force_fz = Udp_RM_Joint.six_force[2]; + udp_sixforce_.force_mx = Udp_RM_Joint.six_force[3]; + udp_sixforce_.force_my = Udp_RM_Joint.six_force[4]; + udp_sixforce_.force_mz = Udp_RM_Joint.six_force[5]; + this->Six_Force_Result->publish(udp_sixforce_); + udp_zeroforce_.force_fx = Udp_RM_Joint.zero_force[0]; + udp_zeroforce_.force_fy = Udp_RM_Joint.zero_force[1]; + udp_zeroforce_.force_fz = Udp_RM_Joint.zero_force[2]; + udp_zeroforce_.force_mx = Udp_RM_Joint.zero_force[3]; + udp_zeroforce_.force_my = Udp_RM_Joint.zero_force[4]; + udp_zeroforce_.force_mz = Udp_RM_Joint.zero_force[5]; + this->Six_Zero_Force_Result->publish(udp_zeroforce_); + } + if(Udp_RM_Joint.control_version == 3) + { + udp_oneforce_.force_fz = Udp_RM_Joint.one_force; + this->One_Force_Result->publish(udp_oneforce_); + udp_onezeroforce_.force_fz = Udp_RM_Joint.one_zero_force; + this->One_Zero_Force_Result->publish(udp_onezeroforce_); + } + if(ctrl_flag == true ) + { + rclcpp::shutdown(); + } + } + else + { + if(come_time == 0) + {Arm_Close();} + come_time++; + while(Arm_Socket_Start_Connect()) + { + if(ctrl_flag == true ) + { + rclcpp::shutdown(); + exit(0); + } + RCLCPP_INFO (this->get_logger(),"Wait for connect "); + sleep(1); + + } + come_time = 0; + connect_state = 0; + connect_state_flag = 0; + Arm_Start(); + RCLCPP_INFO (this->get_logger(),"Connect success\n"); + } +} + +void UdpPublisherNode::heart_timer_callback() +{ + int run_mode; + if(connect_state == 0) + { + // if(robot_handle->id > 0) + // { + // connect_state = 0; + // // RCLCPP_ERROR (this->get_logger(),"Id is %d\n",robot_handle->id); + // } + // else + // { + // connect_state = robot_handle->id; + // if(robot_handle != NULL) + // { + // Rm_Api.rm_delete_robot_arm(robot_handle); + // } + // RCLCPP_ERROR (this->get_logger(),"Arm Disconnect connect id is %d\n",connect_state); + // } + connect_state = Rm_Api.rm_get_arm_run_mode(robot_handle,&run_mode); + if(connect_state !=0) + { + RCLCPP_INFO (this->get_logger(),"connect_state = %d\n",connect_state); + if(connect_state_flag <3) + { + connect_state = 0; + connect_state_flag++; + } + } + } + else + { + if(robot_handle != NULL) + { + Rm_Api.rm_delete_robot_arm(robot_handle); + } + } +} + +bool UdpPublisherNode::read_data() +{ + memset(udp_socket_buffer, 0, sizeof(udp_socket_buffer)); + + ssize_t numBytes = recvfrom(16, udp_socket_buffer, sizeof(udp_socket_buffer), 0, + (struct sockaddr*) & clientAddr, &clientAddrLen); + if (numBytes < 0) { + // std::cerr << "Error in recvfrom" << std::endl; + close(16); + return false; + } + // 将接收到的数据输出到控制台 + udp_socket_buffer[numBytes] = '\0'; // 添加字符串结束符 + std::cout << "Received from " //<< inet_ntoa(clientAddr.sin_addr) + << ":" << ntohs(clientAddr.sin_port) << ": " + << udp_socket_buffer << std::endl; + if((udp_socket_buffer[numBytes-2]==0X0D)&&(udp_socket_buffer[numBytes-1]==0X0A)) + { + return true; + } + else + { + // ROS_ERROR("udp_socket_buffer IS error"); + return false; + } +} + +UdpPublisherNode::UdpPublisherNode(): + rclcpp::Node("udp_publish_node"){ + /*************************************************多线程********************************************/ + callback_group_time1_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + callback_group_time2_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + callback_group_time3_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + /*****************************************************UDP定时器*****************************************************************/ + Udp_Timer = this->create_wall_timer(std::chrono::milliseconds(udp_cycle_g), + std::bind(&UdpPublisherNode::udp_timer_callback,this), callback_group_time1_); + /*****************************************************定时器*****************************************************************/ + Heart_Timer = this->create_wall_timer(std::chrono::milliseconds(500), + std::bind(&UdpPublisherNode::heart_timer_callback,this), callback_group_time2_); + /********************************************************************UDP传输数据**********************************************************/ + Joint_Position_Result = this->create_publisher("joint_states", 10); //发布当前的关节角度 + Arm_Position_Result = this->create_publisher("rm_driver/udp_arm_position", 10); //发布当前的关节姿态 + Six_Force_Result = this->create_publisher("rm_driver/udp_six_force", 10); //发布当前的原始六维力数据 + Six_Zero_Force_Result = this->create_publisher("rm_driver/udp_six_zero_force", 10); //发布当前标坐标系下六维力数据 + One_Force_Result = this->create_publisher("rm_driver/udp_one_force", 10); //发布当前的原始一维力数据 + One_Zero_Force_Result = this->create_publisher("rm_driver/udp_one_zero_force", 10); //发布当前目标坐标系下一维力数据 + Joint_Error_Code_Result = this->create_publisher("rm_driver/udp_joint_error_code", 10); //发布当前的关节错误码 + // Sys_Err_Result = this->create_publisher("rm_driver/udp_sys_err", 10); //发布当前的系统错误码 + Rm_Err_Result = this->create_publisher("rm_driver/udp_rm_err", 10); //发布当前的机械臂错误码 + Arm_Coordinate_Result = this->create_publisher("rm_driver/udp_arm_coordinate", 10); //发布当前六维力数据的基准坐标系 + Hand_Status_Result = this->create_publisher("rm_driver/udp_hand_status", 10); //发布灵巧手状态数据 + + Arm_Current_Status_Result = this->create_publisher("rm_driver/udp_arm_current_status", 10); + Joint_Current_Result = this->create_publisher("rm_driver/udp_joint_current",10); + Joint_En_Flag_Result = this->create_publisher("rm_driver/udp_joint_en_flag",10); + Joint_Pose_Euler_Result = this->create_publisher("rm_driver/udp_joint_pose_euler",10); + Joint_Speed_Result = this->create_publisher("rm_driver/udp_joint_speed",10); + Joint_Temperature_Result = this->create_publisher("rm_driver/udp_joint_temperature",10); + Joint_Voltage_Result = this->create_publisher("rm_driver/udp_joint_voltage",10); + Rm_Plus_Base_Result = this->create_publisher("rm_driver/udp_rm_plus_base",10); + Rm_Plus_State_Result = this->create_publisher("rm_driver/udp_rm_plus_state",10); + } + + +RmArm::~RmArm() +{ + Arm_Close(); +} + +RmArm::RmArm(): + rclcpp::Node("rm_driver"){ + //参数初始化 + this->declare_parameter("arm_ip", "192.168.1.18"); + arm_ip_ = this->get_parameter("arm_ip").as_string(); + + this->declare_parameter("udp_ip", "192.168.1.10"); + udp_ip_ = this->get_parameter("udp_ip").as_string(); + + this->declare_parameter("arm_type", arm_type_); + this->get_parameter("arm_type", arm_type_); + + this->declare_parameter("tcp_port", tcp_port_); + this->get_parameter("tcp_port", tcp_port_); + + this->declare_parameter("udp_port", udp_port_); + this->get_parameter("udp_port", udp_port_); + + this->declare_parameter("arm_dof", arm_dof_); + this->get_parameter("arm_dof", arm_dof_); + + this->declare_parameter("udp_cycle", udp_cycle_); + this->get_parameter("udp_cycle", udp_cycle_); + + this->declare_parameter("udp_force_coordinate", udp_force_coordinate_); + this->get_parameter("udp_force_coordinate", udp_force_coordinate_); + + this->declare_parameter("udp_hand", udp_hand_); + this->get_parameter("udp_hand", udp_hand_); + + this->declare_parameter("udp_plus_base", udp_rm_plus_base_); + this->get_parameter("udp_plus_base", udp_rm_plus_base_); + + this->declare_parameter("udp_plus_state", udp_rm_plus_state_); + this->get_parameter("udp_plus_state", udp_rm_plus_state_); + + this->declare_parameter("trajectory_mode", trajectory_mode_); + this->get_parameter("trajectory_mode", trajectory_mode_); + + this->declare_parameter("radio", radio_); + this->get_parameter("radio", radio_); + + this->declare_parameter("arm_joints", arm_joints); + + udp_cycle_g = udp_cycle_; + if(arm_type_ == "RM_65") + { + // Rm_Api.Service_RM_API_Init(65, NULL); + realman_arm = 65; + } + else if(arm_type_ == "RM_75") + { + // Rm_Api.Service_RM_API_Init(75, NULL); + realman_arm = 75; + } + else if(arm_type_ == "RM_63") + { + // Rm_Api.Service_RM_API_Init(632, NULL); + realman_arm = 63; + } + else if(arm_type_ == "RM_eco65") + { + // Rm_Api.Service_RM_API_Init(651, NULL); + realman_arm = 651; + } + else if(arm_type_ == "RM_eco63") + { + // Rm_Api.Service_RM_API_Init(634, NULL); + realman_arm = 634; + } + else if(arm_type_ == "RM_eco62") + { + // Rm_Api.Service_RM_API_Init(62, NULL); + realman_arm = 62; + } + else if(arm_type_ == "GEN_72") + { + // Rm_Api.Service_RM_API_Init(72, NULL); + realman_arm = 72; + } + tcp_ip = (char*)arm_ip_.c_str(); + + tcp_port = tcp_port_; + udp_hand_g = udp_hand_; + rm_plus_base_g = udp_rm_plus_base_; + rm_plus_state_g = udp_rm_plus_state_; + // RCLCPP_INFO (this->get_logger(),"arm_ip is %s", arm_ip_.c_str()); + while(Arm_Socket_Start_Connect()) + { + if(ctrl_flag == true ) + { + rclcpp::shutdown(); + exit(0); + } + RCLCPP_INFO (this->get_logger(),"Waiting for connect"); + sleep(1); + } + usleep(2000000); + RCLCPP_INFO (this->get_logger(),"%s_driver is running ",arm_type_.c_str()); + /************************************************初始化变量********************************************/ + udp_real_joint_.name.resize(arm_dof_); + udp_real_joint_.position.resize(arm_dof_); + udp_joint_error_code_.joint_error.resize(arm_dof_); + Arm_original_state.joint.resize(arm_dof_); + Arm_state.joint.resize(arm_dof_); + udp_joint_current_.joint_current.resize(arm_dof_); + udp_joint_en_flag_.joint_en_flag.resize(arm_dof_); + udp_joint_speed_.joint_speed.resize(arm_dof_); + udp_joint_temperature_.joint_temperature.resize(arm_dof_); + udp_joint_voltage_.joint_voltage.resize(arm_dof_); + arm_dof_g = arm_dof_; + if (this->get_parameter("arm_joints", arm_joints)) + { + for (int i = 0; i < arm_dof_; i++) + { + udp_real_joint_.name[i] = arm_joints[i]; + // RCLCPP_INFO (this->get_logger(),"arm_joints[%d]: %s", i, arm_joints[i].c_str()); + } + } + /**************************************************end**********************************************/ + + /**********************************************初始化、连接函数****************************************/ + + Arm_Start(); + + /***************************************************end**********************************************/ + + /*************************************************多线程********************************************/ + callback_group_sub1_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto sub_opt1 = rclcpp::SubscriptionOptions(); + sub_opt1.callback_group = callback_group_sub1_; + callback_group_sub2_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto sub_opt2 = rclcpp::SubscriptionOptions(); + sub_opt2.callback_group = callback_group_sub2_; + callback_group_sub3_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto sub_opt3 = rclcpp::SubscriptionOptions(); + sub_opt3.callback_group = callback_group_sub3_; + callback_group_sub4_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto sub_opt4 = rclcpp::SubscriptionOptions(); + sub_opt4.callback_group = callback_group_sub4_; + callback_group_sub5_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto sub_opt5 = rclcpp::SubscriptionOptions(); + sub_opt5.callback_group = callback_group_sub5_; + + Get_Arm_Version();//获取机械臂版本 + Get_Controller_Version();//获取控制器版本 + Set_UDP_Configuration(udp_cycle_, udp_port_, udp_force_coordinate_, udp_ip_, udp_hand_, udp_rm_plus_base_, udp_rm_plus_state_); + + /******************************************************获取udp配置********************************************************************/ + Get_Realtime_Push_Result = this->create_publisher("rm_driver/get_realtime_push_result", rclcpp::ParametersQoS()); + Get_Realtime_Push_Cmd = this->create_subscription("rm_driver/get_realtime_push_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Realtime_Push_Callback,this,std::placeholders::_1), + sub_opt2); + /******************************************************设置udp配置********************************************************************/ + Set_Realtime_Push_Result = this->create_publisher("rm_driver/set_realtime_push_result", rclcpp::ParametersQoS()); + Set_Realtime_Push_Cmd = this->create_subscription("rm_driver/set_realtime_push_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Realtime_Push_Callback,this,std::placeholders::_1), + sub_opt2); +/******************************************************************************end*******************************************************************/ + +/***********************************************************************运动配置**********************************************************************/ + /****************************************MoveJ运动控制*************************************/ + MoveJ_Cmd_Result = this->create_publisher("rm_driver/movej_result", rclcpp::ParametersQoS()); + MoveJ_Cmd = this->create_subscription("rm_driver/movej_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_MoveJ_Callback,this,std::placeholders::_1), + sub_opt4); + /****************************************MoveL运动控制*************************************/ + MoveL_Cmd_Result = this->create_publisher("rm_driver/movel_result", rclcpp::ParametersQoS()); + MoveL_Cmd = this->create_subscription("rm_driver/movel_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_MoveL_Callback,this,std::placeholders::_1), + sub_opt4); + MoveL_offset_Cmd_Result = this->create_publisher("rm_driver/movel_offset_result", rclcpp::ParametersQoS()); + MoveL_offset_Cmd = this->create_subscription("rm_driver/movel_offset_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_MoveL_Offset_Callback,this,std::placeholders::_1), + sub_opt4); + /****************************************MoveC运动控制*************************************/ + MoveC_Cmd_Result = this->create_publisher("rm_driver/movec_result", rclcpp::ParametersQoS()); + MoveC_Cmd = this->create_subscription("rm_driver/movec_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_MoveC_Callback,this,std::placeholders::_1), + sub_opt4); + /******************************************角度透传*****************************************/ + Movej_CANFD_Cmd = this->create_subscription("rm_driver/movej_canfd_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Movej_CANFD_Callback,this,std::placeholders::_1), + sub_opt4); + Movej_CANFD_Custom_Cmd = this->create_subscription("rm_driver/movej_canfd_custom_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Movej_CANFD_Custom_Callback,this,std::placeholders::_1), + sub_opt4); + /*******************************************位姿透传****************************************/ + Movep_CANFD_Cmd = this->create_subscription("rm_driver/movep_canfd_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Movep_CANFD_Callback,this,std::placeholders::_1), + sub_opt4); + Movep_CANFD_Custom_Cmd = this->create_subscription("rm_driver/movep_canfd_custom_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Movep_CANFD_Custom_Callback,this,std::placeholders::_1), + sub_opt4); + /****************************************MoveJ_P运动控制*************************************/ + MoveJ_P_Cmd_Result = this->create_publisher("rm_driver/movej_p_result", rclcpp::ParametersQoS()); + MoveJ_P_Cmd = this->create_subscription("rm_driver/movej_p_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_MoveJ_P_Callback,this,std::placeholders::_1), + sub_opt4); + /***********************************************轨迹急停****************************************/ + Move_Stop_Cmd_Result = this->create_publisher("rm_driver/move_stop_result", rclcpp::ParametersQoS()); + Move_Stop_Cmd = this->create_subscription("rm_driver/move_stop_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Move_Stop_Callback,this,std::placeholders::_1), + sub_opt2); + + Arm_Emergency_Stop_Cmd_Result = this->create_publisher("rm_driver/emergency_stop_result", rclcpp::ParametersQoS()); + Arm_Emergency_Stop_Cmd = this->create_subscription("rm_driver/emergency_stop_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Emergency_Stop_Callback,this,std::placeholders::_1), + sub_opt2); +/******************************************************************************end*******************************************************************/ + +/******************************************************************************示教指令*****************************************************************/ + /*********************************************************关节示教*****************************************************************/ + Set_Joint_Teach_Cmd_Result = this->create_publisher("rm_driver/set_joint_teach_result", rclcpp::ParametersQoS()); + Set_Joint_Teach_Cmd = this->create_subscription("rm_driver/set_joint_teach_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Joint_Teach_Callback,this,std::placeholders::_1), + sub_opt4); + /*********************************************************位置示教*****************************************************************/ + Set_Pos_Teach_Cmd_Result = this->create_publisher("rm_driver/set_pos_teach_result", rclcpp::ParametersQoS()); + Set_Pos_Teach_Cmd = this->create_subscription("rm_driver/set_pos_teach_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Pos_Teach_Callback,this,std::placeholders::_1), + sub_opt4); + /*********************************************************姿态示教*****************************************************************/ + Set_Ort_Teach_Cmd_Result = this->create_publisher("rm_driver/set_ort_teach_result", rclcpp::ParametersQoS()); + Set_Ort_Teach_Cmd = this->create_subscription("rm_driver/set_ort_teach_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Ort_Teach_Callback,this,std::placeholders::_1), + sub_opt4); + /*********************************************************示教停止*****************************************************************/ + Set_Stop_Teach_Cmd_Result = this->create_publisher("rm_driver/set_stop_teach_result", rclcpp::ParametersQoS()); + Set_Stop_Teach_Cmd = this->create_subscription("rm_driver/set_stop_teach_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Stop_Teach_Callback,this,std::placeholders::_1), + sub_opt2); +/******************************************************************************end*****************************************************************/ + +/******************************************************************************四代控制器新增*****************************************************************/ + /************************************************************************查询机械臂基本信息***************************************************************/ + // if(controller_version==4){ + // Get_Arm_Software_Version_Result_v4 = this->create_publisher("rm_driver/get_arm_software_version_result", rclcpp::ParametersQoS()); + // Get_Arm_Software_Version_Cmd = this->create_subscription("rm_driver/get_arm_software_version_cmd",rclcpp::ParametersQoS(), + // std::bind(&RmArm::Arm_Get_Arm_Software_Info_Callback,this,std::placeholders::_1), + // sub_opt2);} + // if(controller_version==3){ + // Get_Arm_Software_Version_Result_v3 = this->create_publisher("rm_driver/get_arm_software_version_result", rclcpp::ParametersQoS()); + // Get_Arm_Software_Version_Cmd = this->create_subscription("rm_driver/get_arm_software_version_cmd",rclcpp::ParametersQoS(), + // std::bind(&RmArm::Arm_Get_Arm_Software_Info_Callback,this,std::placeholders::_1), + // sub_opt2);} + Get_Arm_Software_Version_Result = this->create_publisher("rm_driver/get_arm_software_version_result", rclcpp::ParametersQoS()); + Get_Arm_Software_Version_Cmd = this->create_subscription("rm_driver/get_arm_software_version_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Arm_Software_Info_Callback,this,std::placeholders::_1), + sub_opt2); + /************************************************************************查询软件版本***************************************************************/ + Get_Robot_Info_Result = this->create_publisher("rm_driver/get_robot_info_result", rclcpp::ParametersQoS()); + Get_Robot_Info_Cmd = this->create_subscription("rm_driver/get_robot_info_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Robot_Info_Callback,this,std::placeholders::_1), + sub_opt2); + /************************************************************************查询关节软件版本***************************************************************/ + Get_Joint_Software_Version_Result = this->create_publisher("rm_driver/get_joint_software_version_result", rclcpp::ParametersQoS()); + Get_Joint_Software_Version_Cmd = this->create_subscription("rm_driver/get_joint_software_version_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Joint_Software_Version_Callback,this,std::placeholders::_1), + sub_opt2); + /************************************************************************查询末端接口板软件版本号***************************************************************/ + Get_Tool_Software_Version_Result = this->create_publisher("rm_driver/get_tool_software_version_result", rclcpp::ParametersQoS()); + Get_Tool_Software_Version_Cmd = this->create_subscription("rm_driver/get_tool_software_version_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Tool_Software_Version_Callback,this,std::placeholders::_1), + sub_opt2); + /************************************************************************ 查询流程图运行状态***************************************************************/ + Get_Flowchart_Program_Run_State_Result = this->create_publisher("rm_driver/get_flowchart_program_run_state_result", rclcpp::ParametersQoS()); + Get_Flowchart_Program_Run_State_Cmd = this->create_subscription("rm_driver/get_flowchart_program_run_state_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Flowchart_Program_Run_State_Callback,this,std::placeholders::_1), + sub_opt2); + + /************************************************************************轨迹列表相关***************************************************************/ + Get_Trajectory_File_List_Result = this->create_publisher("rm_driver/get_trajectory_file_list_result", rclcpp::ParametersQoS()); + Get_Trajectory_File_List_Cmd = this->create_subscription("rm_driver/get_trajectory_file_list_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Trajectory_File_List_Callback,this,std::placeholders::_1), + sub_opt2); + Set_Run_Trajectory_Result = this->create_publisher("rm_driver/set_run_trajectory_result", rclcpp::ParametersQoS()); + Set_Run_Trajectory_Cmd = this->create_subscription("rm_driver/set_run_trajectory_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Run_Trajectory_Callback,this,std::placeholders::_1), + sub_opt2); + Delete_Trajectory_File_Result = this->create_publisher("rm_driver/delete_trajectory_file_result", rclcpp::ParametersQoS()); + Delete_Trajectory_File_Cmd = this->create_subscription("rm_driver/delete_trajectory_file_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Delete_Trajectory_File_Callback,this,std::placeholders::_1), + sub_opt2); + Save_Trajectory_File_Result = this->create_publisher("rm_driver/save_trajectory_file_result", rclcpp::ParametersQoS()); + Save_Trajectory_File_Cmd = this->create_subscription("rm_driver/save_trajectory_file_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Save_Trajectory_File_Callback,this,std::placeholders::_1), + sub_opt2); + /************************************************************************Modbus相关***************************************************************/ + /************************************************************************新增Modbus TCP主站***************************************************************/ + Add_Modbus_Tcp_Master_Result = this->create_publisher("rm_driver/add_modbus_tcp_master_result", rclcpp::ParametersQoS()); + Add_Modbus_Tcp_Master_Cmd = this->create_subscription("rm_driver/add_modbus_tcp_master_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Add_Modbus_Tcp_Master_Callback,this,std::placeholders::_1), + sub_opt5); + /************************************************************************更新Modbus TCP主站***************************************************************/ + Update_Modbus_Tcp_Master_Result = this->create_publisher("rm_driver/update_modbus_tcp_master_result", rclcpp::ParametersQoS()); + Update_Modbus_Tcp_Master_Cmd = this->create_subscription("rm_driver/update_modbus_tcp_master_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Update_Modbus_Tcp_Master_Callback,this,std::placeholders::_1), + sub_opt5); + /************************************************************************删除Modbus TCP主站***************************************************************/ + Delete_Modbus_Tcp_Master_Result = this->create_publisher("rm_driver/delete_modbus_tcp_master_result", rclcpp::ParametersQoS()); + Delete_Modbus_Tcp_Master_Cmd = this->create_subscription("rm_driver/delete_modbus_tcp_master_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Delete_Modbus_Tcp_Master_Callback,this,std::placeholders::_1), + sub_opt5); + /************************************************************************查询指定modbus主站*****************************************************************/ + Get_Modbus_Tcp_Master_Result = this->create_publisher("rm_driver/get_modbus_tcp_master_result", rclcpp::ParametersQoS()); + Get_Modbus_Tcp_Master_Cmd = this->create_subscription("rm_driver/get_modbus_tcp_master_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Modbus_Tcp_Master_Callback,this,std::placeholders::_1), + sub_opt5); + /***********************************************************************查询modbus主站列表***********************************************************************/ + Get_Modbus_Tcp_Master_List_Result = this->create_publisher("rm_driver/get_modbus_tcp_master_list_result", rclcpp::ParametersQoS()); + Get_Modbus_Tcp_Master_List_Cmd = this->create_subscription("rm_driver/get_modbus_tcp_master_list_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Modbus_Tcp_Master_List_Callback,this,std::placeholders::_1), + sub_opt5); + /***********************************************************************设置控制器RS485模式(四代控制器支持)***********************************************************************/ + Set_Controller_RS485_Mode_Result = this->create_publisher("rm_driver/set_controller_rs485_mode_result", rclcpp::ParametersQoS()); + Set_Controller_RS485_Mode_Cmd = this->create_subscription("rm_driver/set_controller_rs485_mode_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Controller_RS485_Mode_Callback,this,std::placeholders::_1), + sub_opt5); + /***********************************************************************查询控制器RS485模式(四代控制器支持)***********************************************************************/ + Get_Controller_RS485_Mode_v4_Result = this->create_publisher("rm_driver/get_controller_rs485_mode_result", rclcpp::ParametersQoS()); + Get_Controller_RS485_Mode_v4_Cmd = this->create_subscription("rm_driver/get_controller_rs485_mode_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Controller_RS485_Mode_v4_Callback,this,std::placeholders::_1), + sub_opt5); + /***********************************************************************设置工具端RS485模式(四代控制器支持)***********************************************************************/ + Set_Tool_RS485_Mode_Result = this->create_publisher("rm_driver/set_tool_rs485_mode_result", rclcpp::ParametersQoS()); + Set_Tool_RS485_Mode_Cmd = this->create_subscription("rm_driver/set_tool_rs485_mode_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Set_Tool_RS485_Mode_Callback,this,std::placeholders::_1), + sub_opt5); + /***********************************************************************查询工具端RS485模式(四代控制器支持)***********************************************************************/ + Get_Tool_RS485_Mode_v4_Result = this->create_publisher("rm_driver/get_tool_rs485_mode_v4_result", rclcpp::ParametersQoS()); + Get_Tool_RS485_Mode_v4_Cmd = this->create_subscription("rm_driver/get_tool_rs485_mode_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Tool_RS485_Mode_v4_Callback,this,std::placeholders::_1), + sub_opt2); + + + /***********************************************************************Modbus RTU协议读线圈***********************************************************************/ + Read_Modbus_RTU_Coils_Result = this->create_publisher("rm_driver/read_modbus_rtu_coils_result", rclcpp::ParametersQoS()); + Read_Modbus_RTU_Coils_Cmd = this->create_subscription("rm_driver/read_modbus_rtu_coils_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_RTU_Coils_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus RTU协议写线圈***********************************************************************/ + Write_Modbus_RTU_Coils_Result = this->create_publisher("rm_driver/write_modbus_rtu_coils_result", rclcpp::ParametersQoS()); + Write_Modbus_RTU_Coils_Cmd = this->create_subscription("rm_driver/write_modbus_rtu_coils_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Write_Modbus_RTU_Coils_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus RTU协议读离散量输入***********************************************************************/ + Read_Modbus_RTU_Input_Status_Result = this->create_publisher("rm_driver/read_modbus_rtu_input_status_result", rclcpp::ParametersQoS()); + Read_Modbus_RTU_Input_Status_Cmd = this->create_subscription("rm_driver/read_modbus_rtu_input_status_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_RTU_Input_Status_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus RTU协议读保持寄存器***********************************************************************/ + Read_Modbus_RTU_Holding_Registers_Result = this->create_publisher("rm_driver/read_modbus_rtu_holding_registers_result", rclcpp::ParametersQoS()); + Read_Modbus_RTU_Holding_Registers_Cmd = this->create_subscription("rm_driver/read_modbus_rtu_holding_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_RTU_Holding_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus RTU协议写保持寄存器***********************************************************************/ + Write_Modbus_RTU_Registers_Result = this->create_publisher("rm_driver/write_modbus_rtu_registers_result", rclcpp::ParametersQoS()); + Write_Modbus_RTU_Registers_Cmd = this->create_subscription("rm_driver/write_modbus_rtu_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Write_Modbus_RTU_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus RTU协议读输入寄存器***********************************************************************/ + Read_Modbus_RTU_Input_Registers_Result = this->create_publisher("rm_driver/read_modbus_rtu_input_registers_result", rclcpp::ParametersQoS()); + Read_Modbus_RTU_Input_Registers_Cmd = this->create_subscription("rm_driver/read_modbus_rtu_input_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_RTU_Input_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + + + /***********************************************************************Modbus TCP协议读线圈***********************************************************************/ + Read_Modbus_TCP_Coils_Result = this->create_publisher("rm_driver/read_modbus_tcp_coils_result", rclcpp::ParametersQoS()); + Read_Modbus_TCP_Coils_Cmd = this->create_subscription("rm_driver/read_modbus_tcp_coils_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_TCP_Coils_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus TCP协议写线圈***********************************************************************/ + Write_Modbus_TCP_Coils_Result = this->create_publisher("rm_driver/write_modbus_tcp_coils_result", rclcpp::ParametersQoS()); + Write_Modbus_TCP_Coils_Cmd = this->create_subscription("rm_driver/write_modbus_tcp_coils_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Write_Modbus_TCP_Coils_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus TCP协议读离散量输入***********************************************************************/ + Read_Modbus_TCP_Input_Status_Result = this->create_publisher("rm_driver/read_modbus_tcp_input_status_result", rclcpp::ParametersQoS()); + Read_Modbus_TCP_Input_Status_Cmd = this->create_subscription("rm_driver/read_modbus_tcp_input_status_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_TCP_Input_Status_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus TCP协议读保持寄存器***********************************************************************/ + Read_Modbus_TCP_Holding_Registers_Result = this->create_publisher("rm_driver/read_modbus_tcp_holding_registers_result", rclcpp::ParametersQoS()); + Read_Modbus_TCP_Holding_Registers_Cmd = this->create_subscription("rm_driver/read_modbus_tcp_holding_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_TCP_Holding_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus TCP协议写保持寄存器***********************************************************************/ + Write_Modbus_TCP_Registers_Result = this->create_publisher("rm_driver/write_modbus_tcp_registers_result", rclcpp::ParametersQoS()); + Write_Modbus_TCP_Registers_Cmd = this->create_subscription("rm_driver/write_modbus_tcp_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Write_Modbus_TCP_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************Modbus TCP协议读输入寄存器***********************************************************************/ + Read_Modbus_TCP_Input_Registers_Result = this->create_publisher("rm_driver/read_modbus_tcp_input_registers_result", rclcpp::ParametersQoS()); + Read_Modbus_TCP_Input_Registers_Cmd = this->create_subscription("rm_driver/read_modbus_tcp_input_registers_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Read_Modbus_TCP_Input_Registers_Callback,this,std::placeholders::_1), + sub_opt2); + + /***********************************************************************文件下发***********************************************************************/ + Send_Project_Result = this->create_publisher("rm_driver/send_project_result", rclcpp::ParametersQoS()); + Send_Project_Cmd = this->create_subscription("rm_driver/send_project_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Send_Project_Callback,this,std::placeholders::_1), + sub_opt2); + /***********************************************************************查询在线编程运行状态***********************************************************************/ + Get_Program_Run_State_Result = this->create_publisher("rm_driver/get_program_run_state_result", rclcpp::ParametersQoS()); + Get_Program_Run_State_Cmd = this->create_subscription("rm_driver/get_program_run_state_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Get_Program_Run_State_Callback,this,std::placeholders::_1), + sub_opt2); + + +/******************************************************************************end*****************************************************************/ + +/**********************************************************************透传力位混合控制***********************************************************/ + /******************************************************开启力位混合********************************************************************/ + Start_Force_Position_Move_Result = this->create_publisher("rm_driver/start_force_position_move_result", rclcpp::ParametersQoS()); + Start_Force_Position_Move_Cmd = this->create_subscription("rm_driver/start_force_position_move_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Start_Force_Position_Move_Callback,this,std::placeholders::_1), + sub_opt2); + /********************************************************关闭力位混合*******************************************************************/ + Stop_Force_Position_Move_Result = this->create_publisher("rm_driver/stop_force_position_move_result", rclcpp::ParametersQoS()); + Stop_Force_Position_Move_Cmd = this->create_subscription("rm_driver/stop_force_position_move_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Stop_Force_Position_Move_Callback,this,std::placeholders::_1), + sub_opt2); + /********************************************************角度透传力位混合*****************************************************************/ + Force_Position_Move_Joint_Cmd = this->create_subscription("rm_driver/force_position_move_joint_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Force_Position_Move_Joint_Callback,this,std::placeholders::_1), + sub_opt4); + /********************************************************位姿透传力位混合*****************************************************************/ + Force_Position_Move_Pose_Cmd = this->create_subscription("rm_driver/force_position_move_pose_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Force_Position_Move_Pose_Callback,this,std::placeholders::_1), + sub_opt4); + /********************************************************设置力位混合控制*******************************************************************/ + Set_Force_Postion_Result = this->create_publisher("rm_driver/set_force_postion_result", rclcpp::ParametersQoS()); + Set_Force_Postion_Cmd = this->create_subscription("rm_driver/set_force_postion_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Force_Postion_Callback,this,std::placeholders::_1), + sub_opt4); + /********************************************************结束力位混合控制*******************************************************************/ + Stop_Force_Postion_Result = this->create_publisher("rm_driver/stop_force_postion_result", rclcpp::ParametersQoS()); + Stop_Force_Postion_Cmd = this->create_subscription("rm_driver/stop_force_postion_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Stop_Force_Postion_Callback,this,std::placeholders::_1), + sub_opt4); +/****************************************************************************end******************************************************************/ + +/************************************************************************坐标系指令*************************************************************/ + /**********************************************************切换工作坐标系********************************************************************/ + Change_Work_Frame_Result = this->create_publisher("rm_driver/change_work_frame_result", rclcpp::ParametersQoS()); + Change_Work_Frame_Cmd = this->create_subscription("rm_driver/change_work_frame_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Change_Work_Frame_Callback,this,std::placeholders::_1), + sub_opt2); + /**********************************************************获得工作坐标系********************************************************************/ + Get_Curr_WorkFrame_Result = this->create_publisher("rm_driver/get_curr_workFrame_result", rclcpp::ParametersQoS()); + Get_Curr_WorkFrame_Cmd = this->create_subscription("rm_driver/get_curr_workFrame_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Curr_WorkFrame_Callback,this,std::placeholders::_1), + sub_opt2); + /**********************************************************获得工具坐标系********************************************************************/ + Get_Current_Tool_Frame_Result = this->create_publisher("rm_driver/get_current_tool_frame_result", rclcpp::ParametersQoS()); + Get_Current_Tool_Frame_Cmd = this->create_subscription("rm_driver/get_current_tool_frame_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Current_Tool_Frame_Callback,this,std::placeholders::_1), + sub_opt2); + /**********************************************************获得所有工具坐标系********************************************************************/ + Get_All_Tool_Frame_Result = this->create_publisher("rm_driver/get_all_tool_frame_result", rclcpp::ParametersQoS()); + Get_All_Tool_Frame_Cmd = this->create_subscription("rm_driver/get_all_tool_frame_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_All_Tool_Frame_Callback,this,std::placeholders::_1), + sub_opt2); + /**********************************************************获得所有工作坐标系********************************************************************/ + Get_All_Work_Frame_Result = this->create_publisher("rm_driver/get_all_work_frame_result", rclcpp::ParametersQoS()); + Get_All_Work_Frame_Cmd = this->create_subscription("rm_driver/get_all_work_frame_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_All_Work_Frame_Callback,this,std::placeholders::_1), + sub_opt2); +/*****************************************************************************end***************************************************************/ + + /**********************************************************设置工具端电源输出********************************************************************/ + Set_Tool_Voltage_Result = this->create_publisher("rm_driver/set_tool_voltage_result", rclcpp::ParametersQoS()); + Set_Tool_Voltage_Cmd = this->create_subscription("rm_driver/set_tool_voltage_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Tool_Voltage_Callback,this,std::placeholders::_1), + sub_opt2); + /*****************************************************************************end***************************************************************/ + + /**********************************************************清除机械臂错误码********************************************************************/ + Set_Joint_Err_Clear_Result = this->create_publisher("rm_driver/set_joint_err_clear_result", rclcpp::ParametersQoS()); + Set_Joint_Err_Clear_Cmd = this->create_subscription("rm_driver/set_joint_err_clear_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Joint_Err_Clear_Callback,this,std::placeholders::_1), + sub_opt2); + /*****************************************************************************end***************************************************************/ + +/********************************************************************末端工具-手爪控制****************************************************************/ + /****************************************手爪持续力控夹取**********************************/ + Set_Gripper_Pick_On_Result = this->create_publisher("rm_driver/set_gripper_pick_on_result", rclcpp::ParametersQoS()); + Set_Gripper_Pick_On_Cmd = this->create_subscription("rm_driver/set_gripper_pick_on_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Gripper_Pick_On_Callback,this,std::placeholders::_1), + sub_opt3); + /********************************************手爪力控夹取**********************************/ + Set_Gripper_Pick_Result = this->create_publisher("rm_driver/set_gripper_pick_result", rclcpp::ParametersQoS()); + Set_Gripper_Pick_Cmd = this->create_subscription("rm_driver/set_gripper_pick_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Gripper_Pick_Callback,this,std::placeholders::_1), + sub_opt3); + /*****************************************手爪到达指定位置**********************************/ + Set_Gripper_Position_Result = this->create_publisher("rm_driver/set_gripper_position_result", rclcpp::ParametersQoS()); + Set_Gripper_Position_Cmd = this->create_subscription("rm_driver/set_gripper_position_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Gripper_Position_Callback,this,std::placeholders::_1), + sub_opt3); +/*******************************************************************************end*****************************************************************/ + +/********************************************************************末端工具-五指灵巧手控制************************************************************/ + /****************************************设置灵巧手手势序号**********************************/ + Set_Hand_Posture_Result = this->create_publisher("rm_driver/set_hand_posture_result", rclcpp::ParametersQoS()); + Set_Hand_Posture_Cmd = this->create_subscription("rm_driver/set_hand_posture_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Posture_Callback,this,std::placeholders::_1), + sub_opt3); + /***************************************设置灵巧手动作序列序号*********************************/ + Set_Hand_Seq_Result = this->create_publisher("rm_driver/set_hand_seq_result", rclcpp::ParametersQoS()); + Set_Hand_Seq_Cmd = this->create_subscription("rm_driver/set_hand_seq_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Seq_Callback,this,std::placeholders::_1), + sub_opt3); + /*******************************************设置灵巧手角度************************************/ + Set_Hand_Angle_Result = this->create_publisher("rm_driver/set_hand_angle_result", rclcpp::ParametersQoS()); + Set_Hand_Angle_Cmd = this->create_subscription("rm_driver/set_hand_angle_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Angle_Callback,this,std::placeholders::_1), + sub_opt3); + /*******************************************设置灵巧手速度************************************/ + Set_Hand_Speed_Result = this->create_publisher("rm_driver/set_hand_speed_result", rclcpp::ParametersQoS()); + Set_Hand_Speed_Cmd = this->create_subscription("rm_driver/set_hand_speed_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Speed_Callback,this,std::placeholders::_1), + sub_opt3); + /*******************************************设置灵巧手力度************************************/ + Set_Hand_Force_Result = this->create_publisher("rm_driver/set_hand_force_result", rclcpp::ParametersQoS()); + Set_Hand_Force_Cmd = this->create_subscription("rm_driver/set_hand_force_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Force_Callback,this,std::placeholders::_1), + sub_opt3); + /*******************************************设置灵巧手角度跟随************************************/ + Set_Hand_Follow_Angle_Result = this->create_publisher("rm_driver/set_hand_follow_angle_result", rclcpp::ParametersQoS()); + Set_Hand_Follow_Angle_Cmd = this->create_subscription("rm_driver/set_hand_follow_angle_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Follow_Angle_Callback,this,std::placeholders::_1), + sub_opt3); + /*******************************************设置灵巧手姿势跟随************************************/ + Set_Hand_Follow_Pos_Result = this->create_publisher("rm_driver/set_hand_follow_pos_result", rclcpp::ParametersQoS()); + Set_Hand_Follow_Pos_Cmd = this->create_subscription("rm_driver/set_hand_follow_pos_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Hand_Follow_Pos_Callback,this,std::placeholders::_1), + sub_opt3); +/*******************************************************************************end*****************************************************************/ + +/********************************************************************升降机构************************************************************/ + /****************************************设置升降机构速度**********************************/ + Set_Lift_Speed_Result = this->create_publisher("rm_driver/set_lift_speed_result", rclcpp::ParametersQoS()); + Set_Lift_Speed_Cmd = this->create_subscription("rm_driver/set_lift_speed_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Lift_Speed_Callback,this,std::placeholders::_1), + sub_opt3); + /****************************************设置升降机构高度**********************************/ + Set_Lift_Height_Result = this->create_publisher("rm_driver/set_lift_height_result", rclcpp::ParametersQoS()); + Set_Lift_Height_Cmd = this->create_subscription("rm_driver/set_lift_height_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Set_Lift_Height_Callback,this,std::placeholders::_1), + sub_opt3); + /****************************************获取升降机构状态**********************************/ + Get_Lift_State_Result = this->create_publisher("rm_driver/get_lift_state_result", rclcpp::ParametersQoS()); + Get_Lift_State_Cmd = this->create_subscription("rm_driver/get_lift_state_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Lift_State_Callback,this,std::placeholders::_1), + sub_opt3); +/*******************************************************************************end*****************************************************************/ + + /***************************************************获取机械臂当前状态********************************************/ + Get_Current_Arm_Original_State_Result = this->create_publisher("rm_driver/get_current_arm_original_state_result", rclcpp::ParametersQoS()); + Get_Current_Arm_State_Result = this->create_publisher("rm_driver/get_current_arm_state_result", rclcpp::ParametersQoS()); + Get_Current_Arm_State_Cmd = this->create_subscription("rm_driver/get_current_arm_state_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Current_Arm_State_Callback,this,std::placeholders::_1), + sub_opt2); +/*********************************************************************六维力***************************************************************/ + /*****************************************************六维力数据清零**********************************************/ + Clear_Force_Data_Result = this->create_publisher("rm_driver/clear_force_data_result", rclcpp::ParametersQoS()); + Clear_Force_Data_Cmd = this->create_subscription("rm_driver/clear_force_data_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Clear_Force_Data_Callback,this,std::placeholders::_1), + sub_opt2); + /******************************************************获取六维力数据************************************************/ + /***************************************************传感器受到的外力数据***********************************************/ + Get_Force_Data_Result = this->create_publisher("rm_driver/get_force_data_result", rclcpp::ParametersQoS()); + /***************************************************系统受到的外力数据***********************************************/ + Get_Zero_Force_Result = this->create_publisher("rm_driver/get_zero_force_data_result", rclcpp::ParametersQoS()); + /************************************************工作坐标系下系统受到的外力数据******************************************/ + Get_Work_Zero_Result = this->create_publisher("rm_driver/get_work_force_data_result", rclcpp::ParametersQoS()); + /***********************************************工具坐标系下系统受到的外力数据********************************************/ + Get_Tool_Zero_Result = this->create_publisher("rm_driver/get_tool_force_data_result", rclcpp::ParametersQoS()); + Get_Force_Data_Cmd = this->create_subscription("rm_driver/get_force_data_cmd",rclcpp::ParametersQoS(), + std::bind(&RmArm::Arm_Get_Force_Data_Callback,this,std::placeholders::_1), + sub_opt2); +/*******************************************************************************end*****************************************************************/ +} + + + +int main(int argc, char **argv) { + rclcpp::init(argc, argv); + signal(SIGINT, my_handler); + rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(),8,true); + auto node = std::make_shared(); + auto udpnode = std::make_shared(); + executor.add_node(node); + executor.add_node(udpnode); + executor.spin(); + rclcpp::shutdown(); + return EXIT_SUCCESS; +} \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/CMakeLists.txt new file mode 100644 index 0000000..7d17e3f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/CMakeLists.txt @@ -0,0 +1,59 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_example) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rm_ros_interfaces REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +# include_directories( +# ${PROJECT_SOURCE_DIR} +# ${PROJECT_SOURCE_DIR}/include +# ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME} +# ) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +add_executable(rm_change_work_frame src/api_ChangeWorkFrame_demo.cpp) +add_executable(rm_get_state src/api_Get_Arm_State_demo.cpp) +add_executable(movej_demo src/api_MoveJ_demo.cpp) +add_executable(movejp_demo src/api_MoveJP_demo.cpp) +add_executable(movejp_gen72_demo src/api_MoveJP_Gen72_demo.cpp) +add_executable(movel_demo src/api_MoveL_demo.cpp) +add_executable(movel_gen72_demo src/api_MoveL_Gen72_demo.cpp) + +ament_target_dependencies(rm_change_work_frame rclcpp std_msgs) +ament_target_dependencies(rm_get_state rclcpp std_msgs rm_ros_interfaces) +ament_target_dependencies(movej_demo rclcpp std_msgs rm_ros_interfaces) +ament_target_dependencies(movejp_demo rclcpp std_msgs rm_ros_interfaces) +ament_target_dependencies(movel_demo rclcpp std_msgs rm_ros_interfaces) +ament_target_dependencies(movejp_gen72_demo rclcpp std_msgs rm_ros_interfaces) +ament_target_dependencies(movel_gen72_demo rclcpp std_msgs rm_ros_interfaces) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME}) + +install(TARGETS +rm_change_work_frame rm_get_state movej_demo movejp_demo movel_demo movejp_gen72_demo movel_gen72_demo + DESTINATION lib/${PROJECT_NAME}) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README.md new file mode 100644 index 0000000..a94ee6d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README.md @@ -0,0 +1,210 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_example/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_example/README.md) + +
+ +
+ +# RealMan Robotrm_exampleUser Manual V1.1 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/3 /2024 | Amend(Add GEN72 adapter files) | + +
+ +## Content +* 1.[rm_example Package Description](#rm_example_Package_Description) +* 2.[rm_example Package Use](#rm_example_Package_Use) +* 2.1[Changing the work coordinate system](#Changing_the_work_coordinate_system) +* 2.2[Get the current state message of the robotic arm](#Get_the_current_state_message_of_the_robotic_arm) +* 2.3[MoveJ motion of the robotic arm](#MoveJ_motion_of_the_robotic_arm) +* 2.4[MoveJ_P motion of the robotic arm](#MoveJ_P_motion_of_the_robotic_arm) +* 2.5[MoveL motion of the robotic arm](#MoveL_motion_of_the_robotic_arm) +* 3.[rm_example Package Architecture Description](#rm_example_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4.[rm_example Topic Description](#rm_example_Topic_Description) +* 4.1[rm_change_work_frame topic description](#rm_change_work_frame_topic_description) +* 4.2[rm_get_state topic description](#rm_get_state_topic_description) +* 4.3[movej_demo topic description](#movej_demo_topic_description) +* 4.4[movejp_demo topic description](#movejp_demo_topic_description) +* 4.5[movel_demo topic description](#movel_demo_topic_description) + +## rm_example_Package_Description +rm_bringup package is used for realizing some basic robotic arm functions. And we can also refer to the code to realize other robotic arm functions. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address:https://github.com/RealManRobot/ros2_rm_robot.git. +## rm_example_Package_Use +### Changing_the_work_coordinate_system +First, we need to run the underlying driver node of the robotic arm rm_driver. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, and 75. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +After successfully launching the node, execute the following commands to replace the node in the work coordinate system. +``` +rm@rm-desktop:~$ ros2 run rm_example rm_change_work_frame +``` +The following command pops up to indicate successful replacement. +![image](doc/rm_example11.png) +Enter the following commands in the end for verification, first subscribe to the current work coordinate system topic. +``` +rm@rm-desktop:~$ ros2 topic echo /rm_driver/get_curr_workFrame_result +``` +Then publish the request of the current coordinate system. +``` +rm@rm-desktop:~$ ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" +``` +You can see the following interface pop up at the end. +![image](doc/rm_example1.png) +### Get_the_current_state_message_of_the_robotic_arm +First, we need to run the underlying driver node of the robotic arm rm_driver. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, and 75. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +After successfully launching the node, execute the following commands to obtain the current state of the robotic arm node. +``` +rm@rm-desktop:~$ ros2 run rm_example rm_get_state +``` +The following command pops up to indicate successful replacement. +![image](doc/rm_example2.png) +What is displayed in the interface is the current angle message of the robotic arm, as well as the current end coordinate position and Euler angle posture message of the robotic arm. +### MoveJ_motion_of_the_robotic_arm +Through the following commands, we can control the joint MoveJ motion of the robotic arm. +First, we need to run the underlying driver node of the robotic arm rm_driver. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, and 75. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +After successfully launching the node, execute the following commands to control the movement of the robotic arm. +``` +rm@rm-desktop:~$ ros2 launch rm_example rm__movej.launch.py +``` +dof represents the current degree of freedom message of the arm, and the parameters can be selected as 6dof and 7dof. +For example, when starting the 7-axis robotic arm, the following commands are needed. +``` +rm@rm-desktop:~$ ros2 launch rm_example rm_7dof_movej.launch.py +``` +After successful running, the joint of the robotic arm rotates and the interface displays as follows. +![image](doc/rm_example3.png) +### MoveJ_P_motion_of_the_robotic_arm +Through the following commands, we can control the joint MoveJ_P motion of the robotic arm. +First, we need to run the underlying driver node of the robotic arm rm_driver. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, and 75. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +After successfully launching the node, execute the following commands to control the movement of the robotic arm. +``` +rm@rm-desktop:~$ ros2 run rm_example movejp_demo +``` +Arm version is GEN72, execute the following commands to control the movement of the robotic arm. +``` +rm@rm-desktop:~$ ros2 run rm_example movejp_gen72_demo +``` +After successful execution, the interface appears as follows, and the robotic arm will move to the specified pose. +![image](doc/rm_example4.png) +### MoveL_motion_of_the_robotic_arm +Through the following commands, we can control the joint MoveL motion of the robotic arm. +First, we need to run the underlying driver node of the robotic arm rm_driver. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, and 75. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +After successfully launching the node, execute the following commands to control the movement of the robotic arm. +``` +rm@rm-desktop:~$ ros2 run rm_example movel_demo +``` +Arm version is GEN72, execute the following commands to control the movement of the robotic arm. +``` +rm@rm-desktop:~$ ros2 run rm_example movel_gen72_demo +``` +After successful execution, the interface appears as follows, and the robotic arm performs two motions. Firstly, it moves to the specified pose through MoveJP, and then performs joint motion through MoveL. +![image](doc/rm_example5.png) + +## rm_example_Package_Architecture_Description +### Overview_of_Package_Files +The current rm_example package is composed of the following files. +``` +├── CMakeLists.txt # compilation rule file +├── doc +│ ├── rm_example10.png +│ ├── rm_example11.png +│ ├── rm_example1.png +│ ├── rm_example2.png +│ ├── rm_example3.png +│ ├── rm_example4.png +│ ├── rm_example5.png +│ ├── rm_example6.png +│ ├── rm_example7.png +│ ├── rm_example8.png +│ └── rm_example9.png +├── include +│ └── rm_example +├── launch +│ ├── rm_6dof_movej.launch.py # 6 degrees of freedom MoveJ movement launch file +│ └── rm_7dof_movej.launch.py # 7 degrees of freedom MoveJ movement launch file +├── package.xml +└── src + ├── api_ChangeWorkFrame_demo.cpp # source file to change the work coordinate system + ├── api_Get_Arm_State_demo.cpp # source file to get the robotic arm's state + ├── api_MoveJ_demo.cpp # MoveJ motion source file + ├── api_MoveJP_demo.cpp # MoveJP motion source file + ├── api_MoveJP_Gen72_demo.cpp # GEN72 MoveJP motion source file + ├── api_MoveL_demo.cpp # MoveL motion source file + └── api_MoveL_Gen72_demo.cpp # GEN72 MoveL motion source file +``` +## rm_example_Topic_Description +### rm_change_work_frame_topic_description +The following is the data communication diagram of this node: +![image](doc/rm_example6.png) +You can see that the main communication topics between /changeframe node and /rm_driver are /rm_driver/change_work_frame_result and /rm_driver/change_work_frame_cmd. / rm_driver/change_work_frame_cmd is the release of the switch request and the switch target coordinates, and /rm_driver/change_work_frame_result is the switch result. +### rm_get_state_topic_description +The following is the data communication diagram of this node: +![image](doc/rm_example7.png) +You can see that the main communication topics between the /get_state node and /rm_driver are /rm_driver/get_current_arm_state_cmd and /rm_driver/get_current_arm_original_state_result. / rm_driver/get_current_arm_state_cmd is the request to get the current state of the arm, and /rm_driver/get_current_arm_original_state_result is the switch result. +### movej_demo_topic_description +The following is the data communication diagram of this node: +![image](doc/rm_example8.png) +You can see that the main communication topics between the /Movej_demo node and /rm_driver are /rm_driver/movej_cmd and /rm_driver/movej_result. / rm_driver/movej_cmd is the request to control the motion of the robotic arm, which will release the radian information of each joint that needs to be moved, and /rm_driver/movej_result is the motion result. +### movejp_demo_topic_description +The following is the data communication diagram of this node: +![image](doc/rm_example9.png) +You can see that the main communication topics between the /Movejp_demo_node node and /rm_driver are /rm_driver/movej_p_cmd and rm_driver/movej_p_result. / rm_driver/movej_p_cmd is the request to control the motion planning of the robotic arm, which will publish the coordinates of the target point to be moved, and /rm_driver/movej_p_result is the motion result. +### movel_demo_topic_description +The following is the data communication diagram of this node: +![image](doc/rm_example10.png) +You can see that the main communication topics between the /Movel_demo_node node and /rm_driver are /rm_driver/movej_p_cmd and /rm_driver/movej_p_result, and /rm_driver/movel_cmd and /rm_driver/movel_result. / rm_driver/movej_p_cmd is the request to control the motion planning of the robotic arm, which will publish the coordinates of the target point to be moved first, /rm_driver/movej_p_result is the motion result. After reaching the first point, we reach the second point through linear motion, we can publish the pose of the second point through /rm_driver/movel_cmd, and the topic of /rm_driver/movel_result is the result of the motion. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README_CN.md new file mode 100644 index 0000000..9b99dc3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/README_CN.md @@ -0,0 +1,206 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_example/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_example/README.md) + +
+ +
+ +# 睿尔曼机器人rm_example使用说明书V1.1 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-8 |修订(添加GEN72适配文件) | + +
+ +## 目录 +* 1.[rm_example功能包说明](#rm_example功能包说明) +* 2.[rm_example功能包使用](#rm_example功能包使用) +* 2.1[更换工作坐标系](#更换工作坐标系) +* 2.2[得到当前的机械臂状态信息](#得到当前的机械臂状态信息) +* 2.3[机械臂MoveJ运动](#机械臂MoveJ运动) +* 2.4[机械臂MoveJ_P运动](#机械臂MoveJ_P运动) +* 2.5[机械臂MoveL运动](#机械臂MoveL运动) +* 3.[rm_example功能包架构说明](#rm_example功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4.[rm_example话题说明](#rm_example话题说明) +* 4.1[rm_change_work_frame话题说明](#rm_change_work_frame话题说明) +* 4.2[rm_get_state话题说明](#rm_get_state话题说明) +* 4.3[movej_demo话题说明](#movej_demo话题说明) +* 4.4[movejp_demo话题说明](#movejp_demo话题说明) +* 4.5[movel_demo话题说明](#movel_demo话题说明) + +## rm_example功能包说明 +rm_bringup功能包为实现了一些基本的机械臂功能,通过该功能包我们可以实现机械臂的一些基本的控制功能,还可以参考代码,实现其他的机械臂功能。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用 +## rm_example功能包使用 +### 更换工作坐标系 +首先需要运行机械臂的底层驱动节点rm_driver。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +节点启动成功后,需要执行如下指令运行我们更换工作坐标系的节点。 +``` +rm@rm-desktop:~$ ros2 run rm_example rm_change_work_frame +``` +弹出以下指令代表更换成功。 +![image](doc/rm_example11.png) +可以在终端中输入如下指令进行验证,首先订阅当前的工作坐标系话题。 +``` +rm@rm-desktop:~$ ros2 topic echo /rm_driver/get_curr_workFrame_result +``` +之后发布当前坐标系的请求。 +``` +rm@rm-desktop:~$ ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" +``` +可以看到终端中弹出如下界面。 +![image](doc/rm_example1.png) +### 得到当前的机械臂状态信息 +首先需要运行机械臂的底层驱动节点rm_driver。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +节点启动成功后,需要执行如下指令运行获得机械臂当前状态的节点。 +``` +rm@rm-desktop:~$ ros2 run rm_example rm_get_state +``` +弹出以下指令代表更换成功。 +![image](doc/rm_example2.png) +界面中现实的为机械臂当前的角度信息,以及机械臂当前的末端坐标位置和欧拉角姿态信息。 +### 机械臂MoveJ运动 +通过如下指令可以控制机械臂进行MoveJ关节运动。 +首先需要运行机械臂的底层驱动节点rm_driver。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +节点启动成功后,需要执行如下指令控制机械臂进行运动。 +``` +rm@rm-desktop:~$ ros2 launch rm_example rm__movej.launch.py +``` +命令中的dof代表机械当前的自由度信息,可以选的参数有6dof和7dof。 +例如启动7轴的机械臂时需要使用如下指令。 +``` +rm@rm-desktop:~$ ros2 launch rm_example rm_7dof_movej.launch.py +``` +运行成功后,机械臂的关节将发生转动,且界面将显示如下信息。 +![image](doc/rm_example3.png) +### 机械臂MoveJ_P运动 +通过如下指令可以控制机械臂进行MoveJ_P关节运动。 +首先需要运行机械臂的底层驱动节点rm_driver。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +节点启动成功后,需要执行如下指令控制机械臂进行运动。 +``` +rm@rm-desktop:~$ ros2 run rm_example movejp_demo +``` +若机械臂型号为GEN72则使用如下指令。 +``` +rm@rm-desktop:~$ ros2 run rm_example movejp_gen72_demo +``` +执行成功后界面将出现如下提示,并且机械臂运动到指定位姿。 +![image](doc/rm_example4.png) +### 机械臂MoveL运动 +通过如下指令可以控制机械臂进行MoveL关节运动。 +首先需要运行机械臂的底层驱动节点rm_driver。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm_65_driver.launch.py +``` +节点启动成功后,需要执行如下指令控制机械臂进行运动。 +``` +rm@rm-desktop:~$ ros2 run rm_example movel_demo +``` +若机械臂型号为GEN72则使用如下指令。 +``` +rm@rm-desktop:~$ ros2 run rm_example movel_gen72_demo +``` +执行成功后界面将出现如下提示,并且机械臂将进行两次运动,首先通过MoveJP运动到指定位姿,之后通过MoveL进行关节运动。 +![image](doc/rm_example5.png) + +## rm_example功能包架构说明 +### 功能包文件总览 +当前rm_example功能包文件构成如下。 +``` +├── CMakeLists.txt #编译规则文件 +├── doc +│ ├── rm_example10.png +│ ├── rm_example11.png +│ ├── rm_example1.png +│ ├── rm_example2.png +│ ├── rm_example3.png +│ ├── rm_example4.png +│ ├── rm_example5.png +│ ├── rm_example6.png +│ ├── rm_example7.png +│ ├── rm_example8.png +│ └── rm_example9.png +├── launch +│ ├── rm_6dof_movej.launch.py #6自由度MoveJ运动启动文件 +│ └── rm_7dof_movej.launch.py #7自由度MoveJ运动启动文件 +├── package.xml +└── src + ├── api_ChangeWorkFrame_demo.cpp #更换工作坐标系源文件 + ├── api_Get_Arm_State_demo.cpp #获得机械臂状态源文件 + ├── api_MoveJ_demo.cpp #MoveJ运动源文件 + ├── api_MoveJP_demo.cpp #MoveJP运动源文件 + ├── api_MoveJP_Gen72_demo.cpp #适用于Gen72的MoveJP运动源文件 + └── api_MoveL_demo.cpp #MoveL运动源文件 + └── api_MoveL_Gen72_demo.cpp #适用于Gen72的MoveL运动源文件 +``` +## rm_example话题说明 +### rm_change_work_frame话题说明 +以下为该节点的数据通信图: +![image](doc/rm_example6.png) +可以看到/changeframe节点和/rm_driver之间的主要通信话题为/rm_driver/change_work_frame_result和/rm_driver/change_work_frame_cmd。/rm_driver/change_work_frame_cmd为切换请求和切换目标坐标的发布,/rm_driver/change_work_frame_result为切换结果。 +### rm_get_state话题说明 +以下为该节点的数据通信图: +![image](doc/rm_example7.png) +可以看到/get_state节点和/rm_driver之间的主要通信话题为/rm_driver/get_current_arm_state_cmd和/rm_driver/get_current_arm_original_state_result。/rm_driver/get_current_arm_state_cmd为获取机械臂当前状态请求,/rm_driver/get_current_arm_original_state_result为切换结果。 +### movej_demo话题说明 +以下为该节点的数据通信图: +![image](doc/rm_example8.png) +可以看到/Movej_demo节点和/rm_driver之间的主要通信话题为/rm_driver/movej_cmd和/rm_driver/movej_result。/rm_driver/movej_cmd为控制机械臂运动的请求,将发布需要运动到的各关节的弧度信息,/rm_driver/ movej_result为运动结果。 +### movejp_demo话题说明 +以下为该节点的数据通信图: +![image](doc/rm_example9.png) +可以看到/Movejp_demo_node节点和/rm_driver之间的主要通信话题为/rm_driver/movej_p_cmd和/rm_driver/movej_p_result。/rm_driver/movej_p_cmd为控制机械臂运动规划的请求,将发布需要运动到的目标点的坐标,/rm_driver/ movej_p_result为运动结果。 +### movel_demo话题说明 +以下为该节点的数据通信图: +![image](doc/rm_example10.png) +可以看到/Movel_demo_node节点和/rm_driver之间的主要通信话题为/rm_driver/movej_p_cmd和/rm_driver/movej_p_result还有/rm_driver/movel_cmd和/rm_driver/movel_result。/rm_driver/movej_p_cmd为控制机械臂运动规划的请求,将发布机械臂首先需要运动到的目标点的坐标, /rm_driver/ movej_p_result为运动结果,到达第一个点位后我们通过直线运动到达第二个点位,就可以通过/rm_driver/movel_cmd发布第二个点位的位姿,/rm_driver/movel_result话题代表运动的结果。 + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example1.png new file mode 100644 index 0000000..3cd0fcd Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example10.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example10.png new file mode 100644 index 0000000..940162c Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example10.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example11.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example11.png new file mode 100644 index 0000000..cae811e Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example11.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example2.png new file mode 100644 index 0000000..5071185 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example3.png new file mode 100644 index 0000000..478a55c Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example3.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example4.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example4.png new file mode 100644 index 0000000..30c3046 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example4.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example5.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example5.png new file mode 100644 index 0000000..1baded5 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example5.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example6.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example6.png new file mode 100644 index 0000000..01bb095 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example6.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example7.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example7.png new file mode 100644 index 0000000..e59b1b8 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example7.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example8.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example8.png new file mode 100644 index 0000000..23b2ddf Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example8.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example9.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example9.png new file mode 100644 index 0000000..dae75a6 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/doc/rm_example9.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_6dof_movej.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_6dof_movej.launch.py new file mode 100644 index 0000000..88c6f2e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_6dof_movej.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + movej_node = Node( + package='rm_example', #节点所在的功能包 + executable='movej_demo', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'arm_dof': 6} + ], #接入自由度参数 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(movej_node) + return ld + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_7dof_movej.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_7dof_movej.launch.py new file mode 100644 index 0000000..16d347d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/launch/rm_7dof_movej.launch.py @@ -0,0 +1,17 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +def generate_launch_description(): + ld = LaunchDescription() + movej_node = Node( + package='rm_example', #节点所在的功能包 + executable='movej_demo', #表示要运行的可执行文件名或脚本名字.py + parameters= [ + {'arm_dof': 7} + ], #接入自由度参数 + output='screen', #用于将话题信息打印到屏幕 + ) + + ld.add_action(movej_node) + return ld + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/package.xml new file mode 100644 index 0000000..bf205b6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/package.xml @@ -0,0 +1,21 @@ + + + + rm_example + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + rclcpp + rm_ros_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_ChangeWorkFrame_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_ChangeWorkFrame_demo.cpp new file mode 100644 index 0000000..51285be --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_ChangeWorkFrame_demo.cpp @@ -0,0 +1,69 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class ChangeWorkFrame: public rclcpp::Node +{ + public: + ChangeWorkFrame(); //构造函数 + void change_work_frame_programe(); //改变工作坐标系函数 + void ChangeWorkState_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + private: + + rclcpp::Publisher::SharedPtr publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void ChangeWorkFrame::ChangeWorkState_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******Switching the tool coordinate system succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******Switching the tool coordinate system Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************更换工作坐标系函数****************************************/ +void ChangeWorkFrame::change_work_frame_programe() +{ + std_msgs::msg::String change_work_frame; + change_work_frame.data = "Base"; //可更改工作坐标系位置 + this->publisher_->publish(change_work_frame); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +ChangeWorkFrame::ChangeWorkFrame():rclcpp::Node("changeframe") +{ + subscription_ = this->create_subscription("/rm_driver/change_work_frame_result", rclcpp::ParametersQoS(), std::bind(&ChangeWorkFrame::ChangeWorkState_Callback, this,_1)); + publisher_ = this->create_publisher("/rm_driver/change_work_frame_cmd", rclcpp::ParametersQoS()); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + change_work_frame_programe(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_Get_Arm_State_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_Get_Arm_State_demo.cpp new file mode 100644 index 0000000..16ced00 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_Get_Arm_State_demo.cpp @@ -0,0 +1,72 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/armoriginalstate.hpp" +#include "std_msgs/msg/empty.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class GetArmState: public rclcpp::Node +{ + public: + GetArmState(); //构造函数 + void get_arm_state(); //改变工作坐标系函数 + void GetArmState_Callback(const rm_ros_interfaces::msg::Armoriginalstate & msg); //结果回调函数 + + private: + rclcpp::Publisher::SharedPtr publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void GetArmState::GetArmState_Callback(const rm_ros_interfaces::msg::Armoriginalstate & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.dof == 7) + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf, %lf]\n", msg.joint[0],msg.joint[1],msg.joint[2],msg.joint[3],msg.joint[4],msg.joint[5],msg.joint[6]); + } + else + { + RCLCPP_INFO (this->get_logger(),"joint state is: [%lf, %lf, %lf, %lf, %lf, %lf]\n", msg.joint[0],msg.joint[1],msg.joint[2],msg.joint[3],msg.joint[4],msg.joint[5]); + } + RCLCPP_INFO (this->get_logger(),"pose state is: [%lf, %lf, %lf, %lf, %lf, %lf]\n", msg.pose[0],msg.pose[1],msg.pose[2],msg.pose[3],msg.pose[4],msg.pose[5]); + // RCLCPP_INFO (this->get_logger(),"arm_err is: %d\n",msg.arm_err); + // RCLCPP_INFO (this->get_logger(),"sys_err is: %d\n",msg.sys_err); +} +/***********************************************end**************************************************/ + +/*******************************************获取位姿函数****************************************/ +void GetArmState::get_arm_state() +{ + std_msgs::msg::Empty get_state; + this->publisher_->publish(get_state); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +GetArmState::GetArmState():rclcpp::Node("get_state") +{ + subscription_ = this->create_subscription("/rm_driver/get_current_arm_original_state_result", rclcpp::ParametersQoS(), std::bind(&GetArmState::GetArmState_Callback, this,_1)); + publisher_ = this->create_publisher("/rm_driver/get_current_arm_state_cmd", rclcpp::ParametersQoS()); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + get_arm_state(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_Gen72_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_Gen72_demo.cpp new file mode 100644 index 0000000..8b0158a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_Gen72_demo.cpp @@ -0,0 +1,79 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class MoveJPDemo: public rclcpp::Node +{ + public: + MoveJPDemo(); //构造函数 + void movejp_demo(); //movejp运动规划函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + private: + rclcpp::Publisher::SharedPtr movejp_publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr movejp_subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveJPDemo::MoveJPDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveJP succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveJP Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************获取位姿函数****************************************/ +void MoveJPDemo::movejp_demo() +{ + + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + moveJ_P_TargetPose.pose.position.x = 0.33638298511505127; + moveJ_P_TargetPose.pose.position.y = -0.0025470000691711903; + moveJ_P_TargetPose.pose.position.z = 0.5196430087089539; + moveJ_P_TargetPose.pose.orientation.x = 0.9973419904708862; + moveJ_P_TargetPose.pose.orientation.y = -0.0021510000806301832; + moveJ_P_TargetPose.pose.orientation.z = 0.0628110021352768; + moveJ_P_TargetPose.pose.orientation.w = 0.03685300052165985; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.trajectory_connect = 0; + moveJ_P_TargetPose.block = true; + this->movejp_publisher_->publish(moveJ_P_TargetPose); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveJPDemo::MoveJPDemo():rclcpp::Node("Movejp_demo_node") +{ + + movejp_subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&MoveJPDemo::MoveJPDemo_Callback, this,_1)); + movejp_publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + movejp_demo(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_demo.cpp new file mode 100644 index 0000000..7160ce3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJP_demo.cpp @@ -0,0 +1,79 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class MoveJPDemo: public rclcpp::Node +{ + public: + MoveJPDemo(); //构造函数 + void movejp_demo(); //movejp运动规划函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + private: + rclcpp::Publisher::SharedPtr movejp_publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr movejp_subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveJPDemo::MoveJPDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveJP succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveJP Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************获取位姿函数****************************************/ +void MoveJPDemo::movejp_demo() +{ + + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + moveJ_P_TargetPose.pose.position.x = -0.317239; + moveJ_P_TargetPose.pose.position.y = 0.120903; + moveJ_P_TargetPose.pose.position.z = 0.255765 + 0.04; + moveJ_P_TargetPose.pose.orientation.x = -0.983404; + moveJ_P_TargetPose.pose.orientation.y = -0.178432; + moveJ_P_TargetPose.pose.orientation.z = 0.032271; + moveJ_P_TargetPose.pose.orientation.w = 0.006129; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.trajectory_connect = 0; + moveJ_P_TargetPose.block = true; + this->movejp_publisher_->publish(moveJ_P_TargetPose); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveJPDemo::MoveJPDemo():rclcpp::Node("Movejp_demo_node") +{ + + movejp_subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&MoveJPDemo::MoveJPDemo_Callback, this,_1)); + movejp_publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + movejp_demo(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJ_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJ_demo.cpp new file mode 100644 index 0000000..bb6b060 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveJ_demo.cpp @@ -0,0 +1,100 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movej.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class MoveJDemo: public rclcpp::Node +{ + public: + MoveJDemo(); //构造函数 + void movej_demo(); //发布MoveJ规划指令 + void MovejDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + private: + rclcpp::Publisher::SharedPtr publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr subscription_; //声明订阅器 + rm_ros_interfaces::msg::Movej movej_way; + int arm_dof_ = 6; +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveJDemo::MovejDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******Movej succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******Movej Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************发布movej指令函数****************************************/ +void MoveJDemo::movej_demo() +{ + if(arm_dof_ == 6) + { + movej_way.joint[0] = -0.360829; + movej_way.joint[1] = 0.528468; + movej_way.joint[2] = 1.326293; + movej_way.joint[3] = -0.000454; + movej_way.joint[4] = 1.221748; + movej_way.joint[5] = 0.000052; + movej_way.speed = 20; + movej_way.dof = 6; + } + if(arm_dof_ == 7) + { + movej_way.joint[0] = 0.176278; + movej_way.joint[1] = 0.0; + movej_way.joint[2] = 0.3543; + movej_way.joint[3] = 0.53; + movej_way.joint[4] = 0.00873; + movej_way.joint[5] = 0.3595; + movej_way.joint[6] = 0.3595; + movej_way.speed = 20; + movej_way.dof = 7; + } + movej_way.trajectory_connect = 0; + movej_way.block = true; + this->publisher_->publish(movej_way); +} +/***********************************************end**************************************************/ + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveJDemo::MoveJDemo():rclcpp::Node("Movej_demo") +{ + this->declare_parameter("arm_dof", arm_dof_); + this->get_parameter("arm_dof", arm_dof_); + RCLCPP_INFO (this->get_logger(),"arm_dof is %d\n",arm_dof_); + if(arm_dof_ == 6) + {movej_way.joint.resize(6);} + else if(arm_dof_ == 7) + {movej_way.joint.resize(7);} + subscription_ = this->create_subscription("/rm_driver/movej_result", rclcpp::ParametersQoS(), std::bind(&MoveJDemo::MovejDemo_Callback, this,_1)); + publisher_ = this->create_publisher("/rm_driver/movej_cmd", rclcpp::ParametersQoS()); + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + movej_demo(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_Gen72_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_Gen72_demo.cpp new file mode 100644 index 0000000..d0c7415 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_Gen72_demo.cpp @@ -0,0 +1,129 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "rm_ros_interfaces/msg/movel.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class MoveLDemo: public rclcpp::Node +{ + public: + MoveLDemo(); //构造函数 + void movejp_demo(); //movejp运动规划函数 + void movel_demo(); //movel运动规划函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + void MoveLDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + + private: + rclcpp::Publisher::SharedPtr publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr subscription_; //声明订阅器 + rclcpp::Publisher::SharedPtr movel_publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr movel_subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveLDemo::MoveJPDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveJP succeeded\n"); + /*******************************************movel运动****************************************/ + sleep(1); + rm_ros_interfaces::msg::Movel moveL_TargetPose; + // moveL_TargetPose.pose.position.x = -0.317239; + // moveL_TargetPose.pose.position.y = 0.120903; + // moveL_TargetPose.pose.position.z = 0.295765; + // moveL_TargetPose.pose.orientation.x = -0.983404; + // moveL_TargetPose.pose.orientation.y = -0.178432; + // moveL_TargetPose.pose.orientation.z = 0.032271; + // moveL_TargetPose.pose.orientation.w = 0.006129; + moveL_TargetPose.pose.position.x = 0.3421890139579773; + moveL_TargetPose.pose.position.y = 0.17477799952030182; + moveL_TargetPose.pose.position.z = 0.4847520112991333; + moveL_TargetPose.pose.orientation.x = 0.9892740249633789; + moveL_TargetPose.pose.orientation.y = 0.06573899835348129; + moveL_TargetPose.pose.orientation.z = 0.12849800288677216; + moveL_TargetPose.pose.orientation.w = 0.022433999925851822; + moveL_TargetPose.speed = 20; + moveL_TargetPose.trajectory_connect = 0; + moveL_TargetPose.block = true; + + this->movel_publisher_->publish(moveL_TargetPose); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveJP Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveLDemo::MoveLDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveL succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveL Failed\n"); + } +} +/***********************************************end**************************************************/ + // moveJ_P_TargetPose.pose.position.x = -0.257239; + // moveJ_P_TargetPose.pose.position.y = 0.120903; + // moveJ_P_TargetPose.pose.position.z = 0.205765; + // moveJ_P_TargetPose.pose.orientation.x = -0.983404; + // moveJ_P_TargetPose.pose.orientation.y = -0.178432; + // moveJ_P_TargetPose.pose.orientation.z = 0.032271; + // moveJ_P_TargetPose.pose.orientation.w = 0.006129; +/*******************************************movejp运动函数****************************************/ +void MoveLDemo::movejp_demo() +{ + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + moveJ_P_TargetPose.pose.position.x = 0.3421890139579773; + moveJ_P_TargetPose.pose.position.y = 0.17477799952030182; + moveJ_P_TargetPose.pose.position.z = 0.5347520112991333; + moveJ_P_TargetPose.pose.orientation.x = 0.9892740249633789; + moveJ_P_TargetPose.pose.orientation.y = 0.06573899835348129; + moveJ_P_TargetPose.pose.orientation.z = 0.12849800288677216; + moveJ_P_TargetPose.pose.orientation.w = 0.022433999925851822; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.trajectory_connect = 0; + moveJ_P_TargetPose.block = true; + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + this->publisher_->publish(moveJ_P_TargetPose); +} +/***********************************************end**************************************************/ + + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveLDemo::MoveLDemo():rclcpp::Node("Movel_demo_node") +{ + + subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&MoveLDemo::MoveJPDemo_Callback, this,_1)); + publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + movel_subscription_ = this->create_subscription("/rm_driver/movel_result", rclcpp::ParametersQoS(), std::bind(&MoveLDemo::MoveLDemo_Callback, this,_1)); + movel_publisher_ = this->create_publisher("/rm_driver/movel_cmd", rclcpp::ParametersQoS()); + sleep(1); + movejp_demo(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_demo.cpp b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_demo.cpp new file mode 100644 index 0000000..702dd78 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_example/src/api_MoveL_demo.cpp @@ -0,0 +1,116 @@ +// +// Created by ubuntu on 23-11-28. +// +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "rm_ros_interfaces/msg/movejp.hpp" +#include "rm_ros_interfaces/msg/movel.hpp" +#include "std_msgs/msg/bool.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +/****************************************创建类************************************/ +class MoveLDemo: public rclcpp::Node +{ + public: + MoveLDemo(); //构造函数 + void movejp_demo(); //movejp运动规划函数 + void movel_demo(); //movel运动规划函数 + void MoveJPDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + void MoveLDemo_Callback(const std_msgs::msg::Bool & msg); //结果回调函数 + + + private: + rclcpp::Publisher::SharedPtr publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr subscription_; //声明订阅器 + rclcpp::Publisher::SharedPtr movel_publisher_; //声明发布器 + rclcpp::Subscription::SharedPtr movel_subscription_; //声明订阅器 +}; + + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveLDemo::MoveJPDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveJP succeeded\n"); + /*******************************************movel运动****************************************/ + sleep(1); + rm_ros_interfaces::msg::Movel moveL_TargetPose; + moveL_TargetPose.pose.position.x = -0.317239; + moveL_TargetPose.pose.position.y = 0.120903; + moveL_TargetPose.pose.position.z = 0.295765; + moveL_TargetPose.pose.orientation.x = -0.983404; + moveL_TargetPose.pose.orientation.y = -0.178432; + moveL_TargetPose.pose.orientation.z = 0.032271; + moveL_TargetPose.pose.orientation.w = 0.006129; + moveL_TargetPose.speed = 20; + moveL_TargetPose.trajectory_connect = 0; + moveL_TargetPose.block = true; + + this->movel_publisher_->publish(moveL_TargetPose); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveJP Failed\n"); + } +} +/***********************************************end**************************************************/ + +/******************************接收到订阅的机械臂执行状态消息后,会进入消息回调函数**************************/ +void MoveLDemo::MoveLDemo_Callback(const std_msgs::msg::Bool & msg) +{ + // 将接收到的消息打印出来,显示是否执行成功 + if(msg.data) + { + RCLCPP_INFO (this->get_logger(),"*******MoveL succeeded\n"); + } else { + RCLCPP_INFO (this->get_logger(),"*******MoveL Failed\n"); + } +} +/***********************************************end**************************************************/ + +/*******************************************movejp运动函数****************************************/ +void MoveLDemo::movejp_demo() +{ + rm_ros_interfaces::msg::Movejp moveJ_P_TargetPose; + moveJ_P_TargetPose.pose.position.x = -0.257239; + moveJ_P_TargetPose.pose.position.y = 0.120903; + moveJ_P_TargetPose.pose.position.z = 0.205765; + moveJ_P_TargetPose.pose.orientation.x = -0.983404; + moveJ_P_TargetPose.pose.orientation.y = -0.178432; + moveJ_P_TargetPose.pose.orientation.z = 0.032271; + moveJ_P_TargetPose.pose.orientation.w = 0.006129; + moveJ_P_TargetPose.speed = 20; + moveJ_P_TargetPose.trajectory_connect = 0; + moveJ_P_TargetPose.block = true; + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + this->publisher_->publish(moveJ_P_TargetPose); +} +/***********************************************end**************************************************/ + + +/***********************************构造函数,初始化发布器订阅器****************************************/ +MoveLDemo::MoveLDemo():rclcpp::Node("Movel_demo_node") +{ + + subscription_ = this->create_subscription("/rm_driver/movej_p_result", rclcpp::ParametersQoS(), std::bind(&MoveLDemo::MoveJPDemo_Callback, this,_1)); + publisher_ = this->create_publisher("/rm_driver/movej_p_cmd", rclcpp::ParametersQoS()); + movel_subscription_ = this->create_subscription("/rm_driver/movel_result", rclcpp::ParametersQoS(), std::bind(&MoveLDemo::MoveLDemo_Callback, this,_1)); + movel_publisher_ = this->create_publisher("/rm_driver/movel_cmd", rclcpp::ParametersQoS()); + sleep(1); + movejp_demo(); +} +/***********************************************end**************************************************/ + +/******************************************************主函数*********************************************/ +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/CMakeLists.txt new file mode 100644 index 0000000..8b42cec --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_gazebo) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +install( + DIRECTORY launch config + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README.md new file mode 100644 index 0000000..f5d8ef6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README.md @@ -0,0 +1,114 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_gazebo/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_gazebo/README.md) + +
+ +
+ +# RealMan Robotic Arm rm_gazebo User Manual V1.4 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/3 /2024 | Amend(Add GEN72 adapter files) | +|V1.1.1 | 8/13/2024 | Amend(Add arm type description)| +|V1.2 | 9/10/2024 | Amend(Add ECO63 adapter files) | +|V1.3 | 25/12/2024 | Amend(Add 63, 65, 75, ECO65 six-axis force adapter files and 63, 65, 75, ECO63, ECO65 integrated six-axis force adapter files) | +|V1.4 |2025-4-3 | Amend(AddGen72_IIadapter files) | + +
+ +## Content +* 1.[rm_gazebo Package Description](#rm_gazebo_Package_Description) +* 2.[rm_gazebo Package Running](#rm_gazebo_Package_Running) +* 2.1[Control of the simulation robotic arm](#Control_of_the_simulation_robotic_arm) +* 3.[rm_gazebo Package Architecture Description](#rm_gazebo_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) + +## rm_gazebo_Package_Description +rm_gazebo is mainly used for realizing the simulation function of robot arm Moveit2 planning. We build a virtual robotic arm in the simulation environment of Gazebo, and then control the virtual robot arm in Gazebo through Moveit2. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +Through the introduction of this part, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +Source code address: https://github.com/RealManRobot/ros2_rm_robot.git。 +## rm_gazebo_Package_Running +### Control_of_the_simulation_robotic_arm +After the installation of the environment and the package, we can run the rm_gazebo package. +Use the following command to launch the Gazebo virtual space and the virtual robotic arm. +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo_65_demo.launch.py +``` +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo__6f_demo.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo__6fb_demo.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, 75, and gen72、gen72_II. The interface displays as follows after successful running. +![image](doc/rm_gazebo1.png) +Then, we use the following command to launch moveit2 to control the simulation robot arm in Gazebo. +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo.launch.py +``` +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo_6f.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo_6fb.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, 75, and gen72、gen72_II. +After the control interface of rviz2 pops up, you can perform the simulation control of moveit2 and Gazebo. +![image](doc/rm_gazebo2.png) +## rm_gazebo_Package_Architecture_Description +## Overview_of_Package_Files +The current rm_gazebo package is composed of the following files. +``` +├── CMakeLists.txt # compilation rule file +├── config +│ ├── gazebo_63_6fb_description.urdf.xacro #RML63 integrated six-axis force gazebo launch file +│ ├── gazebo_65_6fb_description.urdf.xacro #RM65 integrated six-axis force gazebo launch file +│ ├── gazebo_75_6fb_description.urdf.xacro #RM75 integrated six-axis force gazebo launch file +│ ├── gazebo_eco63_6fb_description.urdf.xacro #ECO63 integrated six-axis force gazebo launch file +│ ├── gazebo_eco65_6fb_description.urdf.xacro #ECO65 integrated six-axis force gazebo launch file +│ ├── gazebo_63_description.urdf.xacro #63gazebo model description file +│ ├── gazebo_65_description.urdf.xacro #65gazebo model description file +│ ├── gazebo_75_description.urdf.xacro #75gazebo model description file +│ ├── gazebo_eco65_description.urdf.xacro #eco65gazebo model description file +│ ├── gazebo_eco63_description.urdf.xacro #eco63gazebo model description file +│ ├── gazebo_gen72_II_description.urdf.xacro #gen72_IIgazebo model description file +│ └── gazebo_gen72_description.urdf.xacro #gen72gazebo model description file +├── doc +│ ├── rm_gazebo1.png +│ └── rm_gazebo2.png +├── launch +│ ├── gazebo_63_6fb_demo.launch.py #63 integrated six-axis force gazebo launch file +│ ├── gazebo_63_6f_demo.launch.py #63 six-axis force gazebo launch file +│ ├── gazebo_63_demo.launch.py #63 gazebo launch file +│ ├── gazebo_65_6fb_demo.launch.py #RM65 integrated six-axis force gazebo launch file +│ ├── gazebo_65_6f_demo.launch.py #RM65 six-axis force gazebo launch file +│ ├── gazebo_65_demo.launch.py #RM65 gazebo launch file +│ ├── gazebo_75_6fb_demo.launch.py #RM75 integrated six-axis force gazebo launch file +│ ├── gazebo_75_6f_demo.launch.py #RM75 six-axis force gazebo launch file +│ ├── gazebo_75_demo.launch.py #RM75 gazebo launch file +│ ├── gazebo_eco63_6fb_demo.launch.py #ECO63 integrated six-axis force gazebo launch file +│ ├── gazebo_eco63_demo.launch.py #ECO63 gazebo launch file +│ ├── gazebo_eco65_6fb_demo.launch.py #ECO65 integrated six-axis force gazebo launch file +│ ├── gazebo_eco65_6f_demo.launch.py #ECO65 six-axis force gazebo launch file +│ ├── gazebo_eco65_demo.launch.py #ECO65 gazebo launch file +│ ├── gazebo_gen72_II_demo.launch.py #gen72_IIgazebo launch file +│ └── gazebo_gen72_demo.launch.py #gen72gazebo launch file +├── package.xml +├── README_CN.md +└── README.md +``` \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README_CN.md new file mode 100644 index 0000000..9f2078b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/README_CN.md @@ -0,0 +1,112 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_gazebo/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_gazebo/README.md) + +
+ +
+ +# 睿尔曼机器人rm_gazebo使用说明书V1.4 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-8 |修订(添加gen72相关适配文件) | +|V1.1.1 |2024-8-13 |修订(添加机械臂型号适配说明) | +|V1.2 |2024-9-10 |修订(添加eco63相关适配文件) | +|V1.3 |2024-12-25 |修订(添加了63、65、75、ECO65的六维力适配文件,以及63、65、75、ECO63、ECO65的一体化六维力适配文件) | +|V1.4 |2025-4-3 |修订(添加了Gen72_II型适配文件) | + +
+ +## 目录 +* 1.[rm_gazebo功能包说明](#rm_gazebo功能包说明) +* 2.[rm_gazebo功能包运行](#rm_gazebo功能包运行) +* 2.1[控制仿真机械臂](#控制仿真机械臂) +* 3.[rm_gazebo功能包架构说明](#rm_gazebo功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) + +## rm_gazebo功能包说明 +rm_gazebo的主要作用为帮助我们实现机械臂Moveit2规划的仿真功能,我们将在gazebo的仿真环境中搭建一个虚拟机械臂,然后通过Moveit2控制gazebo中的虚拟机械臂。 +* 1.功能包使用。 +* 2.功能包架构说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +### 控制仿真机械臂 +在完成环境安装和功能包安装后,我们可以进行rm_gazebo功能包的运行。 +使用如下指令启动gazebo虚拟空间和虚拟机械臂。 +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo__demo.launch.py +``` +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo__6f_demo.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm_gazebo gazebo__6fb_demo.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72、gen72_II,运行成功后将弹出如下界面。 +![image](doc/rm_gazebo1.png) +之后我们使用如下指令启动moveit2控制gazebo中的仿真机械臂。 +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo.launch.py +``` +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo_6f.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm__config gazebo_moveit_demo_6fb.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72、gen72_II,运行成功后弹出rviz2的控制界面后就可以进行moveit2和gazebo的仿真控制了。 +![image](doc/rm_gazebo2.png) +## rm_gazebo功能包架构说明 +### 功能包文件总览 +当前rm_gazebo功能包的文件构成如下。 +``` +├── CMakeLists.txt #编译规则文件 +├── config +│ ├── gazebo_63_6fb_description.urdf.xacro #RML63一体化六维力gazebo模型描述文件 +│ ├── gazebo_65_6fb_description.urdf.xacro #RM65一体化六维力gazebo模型描述文件 +│ ├── gazebo_75_6fb_description.urdf.xacro #RM75一体化六维力gazebo模型描述文件 +│ ├── gazebo_eco63_6fb_description.urdf.xacro #ECO63一体化六维力gazebo模型描述文件 +│ ├── gazebo_eco65_6fb_description.urdf.xacro #ECO65一体化六维力gazebo模型描述文件 +│ ├── gazebo_63_description.urdf.xacro #RML63gazebo模型描述文件 +│ ├── gazebo_65_description.urdf.xacro #RM65gazebo模型描述文件 +│ ├── gazebo_75_description.urdf.xacro #RM75gazebo模型描述文件 +│ ├── gazebo_eco65_description.urdf.xacro #ECO65gazebo模型描述文件 +│ ├── gazebo_eco63_description.urdf.xacro #ECO63gazebo模型描述文件 +│ ├── gazebo_gen72_description.urdf.xacro #GEN72gazebo模型描述文件 +│ └── gazebo_gen72_II_description.urdf.xacro #GEN72_IIgazebo模型描述文件 +├── doc +│ ├── rm_gazebo1.png +│ └── rm_gazebo2.png +├── include +│ └── rm_gazebo +├── launch +│ ├── gazebo_63_6fb_demo.launch.py #RML63一体化六维力gazebo启动文件 +│ ├── gazebo_63_6f_demo.launch.py #RML63六维力gazebo启动文件 +│ ├── gazebo_63_demo.launch.py #RML63gazebo启动文件 +│ ├── gazebo_65_6fb_demo.launch.py #RM65一体化六维力gazebo启动文件 +│ ├── gazebo_65_6f_demo.launch.py #RM65六维力gazebo启动文件 +│ ├── gazebo_65_demo.launch.py #RM65gazebo启动文件 +│ ├── gazebo_75_6fb_demo.launch.py #RM75一体化六维力gazebo启动文件 +│ ├── gazebo_75_6f_demo.launch.py #RM75六维力gazebo启动文件 +│ ├── gazebo_75_demo.launch.py #RM75gazebo启动文件 +│ ├── gazebo_eco63_6fb_demo.launch.py #ECO63一体化六维力gazebo启动文件 +│ ├── gazebo_eco63_demo.launch.py #ECO63gazebo启动文件 +│ ├── gazebo_eco65_6fb_demo.launch.py #ECO63一体化六维力gazebo启动文件 +│ ├── gazebo_eco65_6f_demo.launch.py #ECO63六维力gazebo启动文件 +│ ├── gazebo_eco65_demo.launch.py #ECO63gazebo启动文件 +│ ├── gazebo_gen72_demo.launch.py #GEN72gazebo启动文件 +│ └── gazebo_gen72_II_demo.launch.py #GEN72_IIgazebo启动文件 +├── package.xml +├── README_CN.md +└── README.md +``` \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_6fb_description.urdf.xacro new file mode 100644 index 0000000..5f6a431 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_6fb_description.urdf.xacro @@ -0,0 +1,115 @@ + + + + + + + + + + + + + + link6_type:=$(arg link6_type) + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_63_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_description.urdf.xacro new file mode 100644 index 0000000..0e2124a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_63_description.urdf.xacro @@ -0,0 +1,113 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_63_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_6fb_description.urdf.xacro new file mode 100644 index 0000000..3e821e2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_6fb_description.urdf.xacro @@ -0,0 +1,115 @@ + + + + + + + + + + + + + + link6_type:=$(arg link6_type) + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_65_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_description.urdf.xacro new file mode 100644 index 0000000..78a1389 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_65_description.urdf.xacro @@ -0,0 +1,113 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_65_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_6fb_description.urdf.xacro new file mode 100644 index 0000000..34456aa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_6fb_description.urdf.xacro @@ -0,0 +1,127 @@ + + + + + + + + + + + + + + link7_type:=$(arg link7_type) + + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_75_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_description.urdf.xacro new file mode 100644 index 0000000..bf2299b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_75_description.urdf.xacro @@ -0,0 +1,124 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_75_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_6fb_description.urdf.xacro new file mode 100644 index 0000000..9dfbcb9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_6fb_description.urdf.xacro @@ -0,0 +1,116 @@ + + + + + + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_eco63_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_description.urdf.xacro new file mode 100644 index 0000000..fda7404 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco63_description.urdf.xacro @@ -0,0 +1,113 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_eco63_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_6fb_description.urdf.xacro new file mode 100644 index 0000000..1310220 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_6fb_description.urdf.xacro @@ -0,0 +1,116 @@ + + + + + + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_eco65_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_description.urdf.xacro new file mode 100644 index 0000000..da24864 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_eco65_description.urdf.xacro @@ -0,0 +1,113 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/Purple + false + false + + + Gazebo/Red + false + + + Gazebo/Blue + false + + + Gazebo/Green + false + + + Gazebo/Yellow + false + + + Gazebo/Orange + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_eco65_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_II_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_II_description.urdf.xacro new file mode 100644 index 0000000..8b42617 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_II_description.urdf.xacro @@ -0,0 +1,124 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_gen72_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_description.urdf.xacro new file mode 100644 index 0000000..217c7c5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/config/gazebo_gen72_description.urdf.xacro @@ -0,0 +1,124 @@ + + + + + + + + + + + + + + + + + false + false + + + Gazebo/White + false + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + Gazebo/White + false + + + + + true + true + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + $(find rm_gen72_config)/config/ros2_controllers.yaml + robot_description + robot_state_publisher + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo1.png new file mode 100644 index 0000000..503d14b Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo2.png new file mode 100644 index 0000000..c78e041 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/doc/rm_gazebo2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6f_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6f_demo.launch.py new file mode 100755 index 0000000..67287b7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6f_demo.launch.py @@ -0,0 +1,95 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rml_63_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_63_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link6_type": "Link6_6f"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # gazebo = IncludeLaunchDescription( + # PythonLaunchDescriptionSource([os.path.join( + # get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + # ) + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6fb_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6fb_demo.launch.py new file mode 100755 index 0000000..e2fcc5e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_6fb_demo.launch.py @@ -0,0 +1,95 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rml_63_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_63_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link6_type": "Link6_6fb"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # gazebo = IncludeLaunchDescription( + # PythonLaunchDescriptionSource([os.path.join( + # get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + # ) + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_demo.launch.py new file mode 100755 index 0000000..f55a20b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_63_demo.launch.py @@ -0,0 +1,95 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rml_63_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_63_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # gazebo = IncludeLaunchDescription( + # PythonLaunchDescriptionSource([os.path.join( + # get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + # ) + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6f_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6f_demo.launch.py new file mode 100755 index 0000000..697159c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6f_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_65_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link6_type": "Link6_6f"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点? + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + # moveit是怎么和gazebo这里提供的action连接起来的 + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6fb_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6fb_demo.launch.py new file mode 100755 index 0000000..3ae2654 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_6fb_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_65_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link6_type": "Link6_6fb"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点? + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + # moveit是怎么和gazebo这里提供的action连接起来的 + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_demo.launch.py new file mode 100755 index 0000000..d1b1fea --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_65_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_65_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点? + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action? + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + # moveit是怎么和gazebo这里提供的action连接起来的 + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6f_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6f_demo.launch.py new file mode 100755 index 0000000..efecfb0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6f_demo.launch.py @@ -0,0 +1,90 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_75_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_75_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link7_type": "Link7_6f"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6fb_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6fb_demo.launch.py new file mode 100755 index 0000000..f5b0e84 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_6fb_demo.launch.py @@ -0,0 +1,90 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_75_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_75_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link7_type": "Link7_6fb"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_demo.launch.py new file mode 100755 index 0000000..a769be1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_75_demo.launch.py @@ -0,0 +1,90 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_75_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_75_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_6fb_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_6fb_demo.launch.py new file mode 100755 index 0000000..fecc788 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_6fb_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_eco63_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_eco63_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc,mappings={"link6_type": "Link6_6fb"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + # 这些节点、话题的名称可不可以自定义 + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_demo.launch.py new file mode 100755 index 0000000..b9c2f9c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco63_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_eco63_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_eco63_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + # 这些节点、话题的名称可不可以自定义 + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6f_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6f_demo.launch.py new file mode 100755 index 0000000..c5832d6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6f_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_eco65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_eco65_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc, mappings={"link6_type": "Link6_6f"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + # 这些节点、话题的名称可不可以自定义 + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6fb_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6fb_demo.launch.py new file mode 100755 index 0000000..a9de54b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_6fb_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_eco65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_eco65_6fb_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc, mappings={"link6_type": "Link6_6fb"}) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + # 这些节点、话题的名称可不可以自定义 + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_demo.launch.py new file mode 100755 index 0000000..b466d5f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_eco65_demo.launch.py @@ -0,0 +1,91 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_eco65_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_eco65_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + # 这些节点、话题的名称可不可以自定义 + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_II_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_II_demo.launch.py new file mode 100755 index 0000000..ffcdad8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_II_demo.launch.py @@ -0,0 +1,90 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_gen72_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_gen72_II_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_demo.launch.py new file mode 100755 index 0000000..ae48324 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/launch/gazebo_gen72_demo.launch.py @@ -0,0 +1,90 @@ +import os +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch.event_handlers import OnProcessExit + +from ament_index_python.packages import get_package_share_directory + +import xacro + +def generate_launch_description(): + package_name = 'rm_gazebo' + + robot_name_in_model = 'rm_gen72_description' + + pkg_share = FindPackageShare(package=package_name).find(package_name) + urdf_model_path = os.path.join(pkg_share, f'config/gazebo_gen72_description.urdf.xacro') + + + print("---", urdf_model_path) + + doc = xacro.parse(open(urdf_model_path)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + print("urdf", doc.toxml()) + + # 启动gazebo + gazebo = ExecuteProcess( + cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], + output='screen') + + # 启动了robot_state_publisher节点后,该节点会发布 robot_description 话题,话题内容是模型文件urdf的内容 + # 并且会订阅 /joint_states 话题,获取关节的数据,然后发布tf和tf_static话题. + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'use_sim_time': True}, params, {"publish_frequency":15.0}], + output='screen' + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', f'{robot_name_in_model}'], + output='screen') + + # gazebo在加载urdf时,根据urdf的设定,会启动一个joint_states节点 + # 关节状态发布器 + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + # 路径执行控制器,也就是那个action + # 这个rm_group_controller需要根据urdf文件里面引用的ros2_controllers.yaml里面的名字确定 + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'rm_group_controller'], + output='screen' + ) + + # 用下面这两个估计是想控制好各个节点的启动顺序 + # 监听 spawn_entity_cmd,当其退出(完全启动)时,启动load_joint_state_controller + close_evt1 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ) + # 监听 load_joint_state_controller,当其退出(完全启动)时,启动load_joint_trajectory_controller + close_evt2 = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ) + + ld = LaunchDescription([ + close_evt1, + close_evt2, + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/package.xml new file mode 100644 index 0000000..1004efc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_gazebo/package.xml @@ -0,0 +1,52 @@ + + + + rm_gazebo + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_65_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_65_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/CMakeLists.txt new file mode 100644 index 0000000..567320b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_install) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf new file mode 100644 index 0000000..999e474 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/doc/0. 睿尔曼 l ROS2机械臂rm_install包详解V1.0.pdf differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/package.xml new file mode 100644 index 0000000..317eee4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/package.xml @@ -0,0 +1,18 @@ + + + + rm_install + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/lib_install.sh b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/lib_install.sh new file mode 100755 index 0000000..fcbd319 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/lib_install.sh @@ -0,0 +1,74 @@ +#!/bin/bash +# Version: 1.4 +# Date: 2023-06-19 +# Author: Herman Ye @Realman Robotics +# Warning: This script is ONLY for ROS2 Humble in ubuntu 20.04 +# set -x +set -e + + + +# UBUNTU CONFIGURATION BEGINS HERE + +# Check if script is run as root (sudo) +if [ "$(id -u)" != "0" ]; then + echo "This script must be run with sudo privileges. for example: sudo bash ros2_humble_install.sh" + read -p "Press any key to exit..." + exit 1 +fi + + +if [ $(uname -m) = "x86_64" ]; then + sudo rm libRM_Service.so* + sudo tar -jxvf linux_x86_service_release* + + if [ -f "/usr/local/lib/linux_x86_service_release*" ];then + echo "find file" + sudo rm /usr/local/lib/libRM_Service.so* + sudo rm /usr/local/lib/linux_x86_service_release* + fi + sudo cp linux_x86_service_release* /usr/local/lib + cd /usr/local/lib + sudo tar -jxvf /usr/local/lib/linux_x86_service_release* +else + sudo rm libRM_Service.so* + sudo tar -jxvf linux_arm_service_release* + + if [ -f "/usr/local/lib/linux_arm_service_release*" ];then + sudo rm /usr/local/lib/libRM_Service.so* + sudo rm /usr/local/lib/inux_arm_service_release* + fi + sudo cp linux_arm_service_release* /usr/local/lib + cd /usr/local/lib + sudo tar -jxvf /usr/local/lib/linux_arm_service_release* +fi +if ! grep -q "/usr/local/lib" /etc/ld.so.conf; then + echo "/usr/local/lib" | sudo tee -a /etc/ld.so.conf +else + echo "/usr/local/lib is already set in /etc/ld.so.conf" +fi +sudo /sbin/ldconfig +cd ~ +TEXT1="Lib installation completed!" +TEXT1_PADDING=$((($TERMINAL_WIDTH-${#TEXT1})/2)) +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo -e "${GREEN}$(printf '%*s' $TEXT1_PADDING)${TEXT1} ${NC}" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/moveit2_install.sh b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/moveit2_install.sh new file mode 100755 index 0000000..333b49e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/moveit2_install.sh @@ -0,0 +1,207 @@ +#!/bin/bash +# Version: 1.3 +# Date: 2023-07-19 +# Author: Herman Ye @Realman Robotics +# +# Warning: This script assumes that the ubuntu20.04 system and ROS2 Foxy have been installed correctly +# If not, please execute ROS2_Foxy_install.sh first. +# +# set -x +set -e + +# Get script directory +SCRIPT_DIR=$(dirname "$0") +# Get the username of the non-root user +USERNAME=$SUDO_USER +echo "Current user is: $USERNAME" + +# Check if script is run as root (sudo) +if [ "$(id -u)" != "0" ]; then + echo "This script must be run with sudo privileges. for example: sudo bash moveit2_install.sh" + read -p "Press any key to exit..." + exit 1 +fi +echo "sudo privileges check passed" + +# Check if script is run in ubuntu20.04 +if [ "$(lsb_release -sc)" != "focal" ]; then + if [ "$(lsb_release -sc)" != "jammy" ]; then + echo "This script must be run in ubuntu20.04 or 22.04" + read -p "Press any key to exit..." + exit 1 + fi +fi + +echo "Ubuntu version check passed" + +# Check if script is run in ROS2 Foxy +if [[ "$(sudo -u $USERNAME dpkg -l ros-foxy-desktop)" == *ii* ]]; then + echo "ROS2 foxy check passed" +elif [[ "$(sudo -u $USERNAME dpkg -l ros-humble-desktop)" == *ii* ]]; then + echo "ROS2 humble check passed" +else + echo "This script must be run with ROS2 HumbleorFoxy-desktop-full" + read -p "Press any key to exit..." + exit 1 +fi + +# Save logs to files +LOG_FILE="${SCRIPT_DIR}/moveit2_install.log" +ERR_FILE="${SCRIPT_DIR}/moveit2_install.err" +rm -f ${LOG_FILE} +rm -f ${ERR_FILE} + +# Redirect output to console and log files +exec 1> >(tee -a ${LOG_FILE} ) +exec 2> >(tee -a ${ERR_FILE} >&2) + +# Add GitHub520 Host to host for GitHub access in China +# https://github.com/521xueweihan/GitHub520 +sudo apt-get install curl -y +sudo sed -i "/# GitHub520 Host Start/Q" /etc/hosts && curl https://raw.hellogithub.com/hosts >> /etc/hosts +echo "GitHub520 Host added to host file" +# sudo sed -i 's/#DNS=/DNS=114.114.114.114/' /etc/systemd/resolved.conf +# echo "DNS server changed to 114.114.114.114" +sudo systemctl restart systemd-resolved.service +echo "Refreshed network settings, sleep 5 seconds" +sleep 5 + +# Install wstool +sudo apt-get install python3-wstool -y + +if [ "$(lsb_release -sc)" = "focal" ]; then + # Install moveit + sudo apt-get install ros-foxy-moveit -y + # sudo apt-get install ros-foxy-moveit-visual-tools -y + # Warning: Installing all subpackages of moveit may cause dependency conflicts, please do so with caution. + sudo apt-get install ros-foxy-moveit-* -y + # Install ros_control + sudo apt-get install ros-foxy-controller-interface ros-foxy-controller-manager-msgs ros-foxy-controller-manager +elif [ "$(lsb_release -sc)" = "jammy" ]; then + # Install moveit + sudo apt-get install ros-humble-moveit -y + # sudo apt-get install ros-foxy-moveit-visual-tools -y + # Warning: Installing all subpackages of moveit may cause dependency conflicts, please do so with caution. + sudo apt-get install ros-humble-moveit-* -y + # Install ros_control + sudo apt-get install ros-humble-controller-interface ros-humble-controller-manager-msgs ros-humble-controller-manager +fi +# Create A Catkin Workspace and Download MoveIt Source + + +clear +sleep 1 + +# Define the variables to be printed +TEXT0="" +TEXT1="Moveit installation completed!" +TEXT2="Please open a new terminal and run roslaunch to verify the installation:" +TEXT3="roslaunch panda_moveit_config demo.launch" +TEXT4="1. Click 'Add' in the left panel, and add the following items:" +TEXT5="2. Add 'RobotModel', 'MotionPlanning' to the left panel" +TEXT6="3. Try to drag the end effector to see if the robot arm moves" +TEXT7="4. Click 'Plan & Execute' to see the robot arm move" +TEXT8="5. If you see the robot arm move, the installation is successful" +# Define the colors +RED='\033[0;31m' +BLUE='\033[0;34m' +GREEN='\033[1;32m' +NC='\033[0m' + +# Calculate the center of the terminal window +TERMINAL_WIDTH=$(tput cols) +TEXT1_PADDING=$((($TERMINAL_WIDTH-${#TEXT1})/2)) +TEXT2_PADDING=$((($TERMINAL_WIDTH-${#TEXT2})/2)) +TEXT3_PADDING=$((($TERMINAL_WIDTH-${#TEXT3})/2)) + +# Finished +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${GREEN}$(printf '%*s' $TEXT1_PADDING)${TEXT1} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# read -rp "Do you want to download the tutorial code? (y/n) " confirm +# if [[ "$confirm" =~ ^[Yy]$ ]]; then +# # Download Example Code(already in the moveit.rosinstall) +# # cd /home/$USERNAME/ws_moveit/src +# sudo rm -rf /home/$USERNAME/ws_moveit +# mkdir -p /home/$USERNAME/ws_moveit/src +# cd /home/$USERNAME/ws_moveit/src +# clear +# echo "Connecting to GitHub, please wait..." +# echo "If the download stuck here for a long time" +# echo "please check your network connection and rerun this script" +# # install franka robot as demo +# sudo apt-get install ros-foxy-franka-* -y +# git clone https://github.com/ros-planning/moveit_tutorials.git -b master +# git clone https://github.com/ros-planning/panda_moveit_config.git -b Foxy-devel + +# # git clone https://github.com/ros-controls/ros_control.git -b Foxy-devel + +# # Clone MoveIt packages from source +# # git clone https://github.com/ros-planning/moveit_msgs.git +# # git clone https://github.com/ros-planning/moveit_resources.git +# # git clone https://github.com/ros-planning/geometric_shapes.git --branch Foxy-devel +# # git clone https://github.com/ros-planning/srdfdom.git --branch Foxy-devel +# # git clone https://github.com/ros-planning/moveit.git +# # git clone https://github.com/PickNikRobotics/rviz_visual_tools.git +# # git clone https://github.com/ros-planning/moveit_visual_tools.git +# # git clone https://github.com/ros-planning/moveit_tutorials.git +# # git clone https://github.com/ros-planning/panda_moveit_config.git --branch Foxy-devel +# # Rosdepc install +# cd /home/$USERNAME/ws_moveit/src +# rosdepc install -y --from-paths . --ignore-src --rosdistro Foxy > /dev/null +# echo "Rosdep install finished" + +# # Build the Workspace +# cd /home/$USERNAME/ws_moveit +# catkin config --extend /opt/ros/Foxy --cmake-args -DCMAKE_BUILD_TYPE=Release +# catkin init +# catkin build + +# # Environment setup +# if ! grep -q "/home/$USERNAME/ws_moveit/devel/setup.bash" /home/$USERNAME/.bashrc; then + +# echo "# ws_moveit Environment Setting" | sudo tee -a /home/$USERNAME/.bashrc +# echo "source /home/$USERNAME/ws_moveit/devel/setup.bash" >> /home/$USERNAME/.bashrc +# echo "ws_moveit environment setup added to /home/$USERNAME/.bashrc" +# else +# echo "ws_moveit environment is already set in /home/$USERNAME/.bashrc" +# fi +# source /home/$USERNAME/.bashrc + +# # Verifying Moveit1 installation +# clear + + +# # Print the text in the center of the screen in the desired colors +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${GREEN}$(printf '%*s' $TEXT1_PADDING)${TEXT1} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT2} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${RED}$(printf '%*s' $TEXT3_PADDING)${TEXT3} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT4} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT5} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT6} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT7} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT8} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT0} ${NC}" +# echo -e "${NC}$(printf '%*s' $TEXT1_PADDING)${TEXT0} ${NC}" +# else +read -p "Ok. The installation is complete. Press any key to exit..." +exit 0 +# fi diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/ros2_install.sh b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/ros2_install.sh new file mode 100755 index 0000000..af76c26 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/scripts/ros2_install.sh @@ -0,0 +1,227 @@ +#!/bin/bash +# Version: 1.4 +# Date: 2023-06-19 +# Author: Herman Ye @Realman Robotics +# Warning: This script is ONLY for ROS2 Humble in ubuntu 20.04 +# set -x +set -e + + + +# UBUNTU CONFIGURATION BEGINS HERE + +# Check if script is run as root (sudo) +if [ "$(id -u)" != "0" ]; then + echo "This script must be run with sudo privileges. for example: sudo bash ros2_humble_install.sh" + read -p "Press any key to exit..." + exit 1 +fi +# Get script directory +SCRIPT_DIR=$(dirname "$0") +# Get the username of the non-root user +USERNAME=$SUDO_USER +Ubuntu_version=$(lsb_release -r --short) +echo "Current user is: $USERNAME" +# Save logs to files +LOG_FILE="${SCRIPT_DIR}/ros2_humble_install.log" +ERR_FILE="${SCRIPT_DIR}/ros2_humble_install.err" +rm -f ${LOG_FILE} +rm -f ${ERR_FILE} + +# Redirect output to console and log files +exec 1> >(tee -a ${LOG_FILE} ) +exec 2> >(tee -a ${ERR_FILE} >&2) + +# Output log info to console +echo "ROS2 Humble installation started!" +echo "Installation logs will be saved to ${LOG_FILE}" +echo "Installation errors will be saved to ${ERR_FILE}" + +# No Password sudo config +sudo sed -i 's/^%sudo.*/%sudo ALL=(ALL) NOPASSWD:ALL/g' /etc/sudoers + +# Get architecture of the system +if [ $(uname -m) = "x86_64" ]; then + MIRROR="https://mirrors.tuna.tsinghua.edu.cn/ubuntu/" +else + MIRROR="https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/" +fi +echo "Current system architecture is: $(uname -m)" +echo "Current mirror is: $MIRROR" +if [ $Ubuntu_version = "20.04" ]; then + +# Backup original software sources +sudo cp /etc/apt/sources.list /etc/apt/sources.list.backup +sudo cp /etc/apt/sources.list /etc/apt/sources.list.d/realman_ros2.list +# Clear original software sources +sudo echo "" > /etc/apt/sources.list +sudo echo "" > /etc/apt/sources.list.d/realman_ros2.list + +# Replace software sources +echo "deb $MIRROR focal main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb $MIRROR focal-updates main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb $MIRROR focal-backports main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb [arch=$(dpkg --print-architecture)] https://mirrors.tuna.tsinghua.edu.cn/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" >> /etc/apt/sources.list.d/realman_ros2.list + + +if [ $(uname -m) = "x86_64" ]; then + echo "deb http://security.ubuntu.com/ubuntu/ focal-security main restricted universe multiverse" >> /etc/apt/sources.list +else + echo "deb http://ports.ubuntu.com/ubuntu-ports/ focal-security main restricted universe multiverse" >> /etc/apt/sources.list +fi + +elif [ $Ubuntu_version = "22.04" ]; then +# Backup original software sources +sudo cp /etc/apt/sources.list /etc/apt/sources.list.backup +sudo cp /etc/apt/sources.list /etc/apt/sources.list.d/realman_ros2.list +# Clear original software sources +sudo echo "" > /etc/apt/sources.list +sudo echo "" > /etc/apt/sources.list.d/realman_ros2.list + +# Replace software sources +echo "deb $MIRROR jammy main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb $MIRROR jammy-updates main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb $MIRROR jammy-backports main restricted universe multiverse" >> /etc/apt/sources.list +echo "deb [arch=$(dpkg --print-architecture)] https://mirrors.tuna.tsinghua.edu.cn/ros2/ubuntu jammy main" >> /etc/apt/sources.list.d/realman_ros2.list +if [ $(uname -m) = "x86_64" ]; then + echo "deb http://security.ubuntu.com/ubuntu/ jammy-security main restricted universe multiverse" >> /etc/apt/sources.list +else + echo "deb http://ports.ubuntu.com/ubuntu-ports/ jammy-security main restricted universe multiverse" >> /etc/apt/sources.list +fi + +else + echo "This script must be run with Ubuntu 20.04 or 22.04" + read -p "Press any key to exit..." + exit 1 +fi + +# Install Curl +sudo apt-get install curl -y # If you haven't already installed curl +sudo apt-get install software-properties-common -y +sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + +# System update +sudo apt-get update +sudo apt-get upgrade -y + + +# Install pip +sudo apt-get install python3-dev -y +sudo apt-get install pip -y # If you haven't already installed pip + +# Install gnome-terminal +sudo apt-get install gnome-terminal -y # If you haven't already installed gnome-terminal + +# Set default pip source +pip config set global.index-url http://pypi.tuna.tsinghua.edu.cn/simple +pip config set global.trusted-host pypi.tuna.tsinghua.edu.cn + +# Add the ROS key +# ros_key="${SCRIPT_DIR}/ros.key" +# rm -f "${ros_key}" +# wget http://packages.ros.org/ros.key +# sudo apt-key add ros.key + +#First ensure that the Ubuntu Universe repository is enabled. +sudo apt-get install software-properties-common -y +sudo add-apt-repository universe + +# Update the system packages index to the latest version + +sudo apt-get update + +# Install ROS2 Humble +if [ $Ubuntu_version = "20.04" ]; then + sudo apt-get install ros-foxy-desktop python3-argcomplete -y + sudo apt-get install gazebo11 -y + sudo apt-get install ros-foxy-gazebo-* -y +elif [ $Ubuntu_version = "22.04" ]; then + sudo apt-get install ros-humble-desktop -y + sudo apt-get install gazebo -y + sudo apt-get install ros-humble-gazebo-* -y +fi + +sudo apt-get install ros-dev-tools -y + +# Environment setup +if [ $Ubuntu_version = "20.04" ]; then + if ! grep -q "source /opt/ros/foxy/setup.bash" /home/$USERNAME/.bashrc; then + + echo "# ROS2 foxy Environment Setting" | sudo tee -a /home/$USERNAME/.bashrc + echo "source /opt/ros/foxy/setup.bash" | sudo tee -a /home/$USERNAME/.bashrc + echo "ROS2 foxy environment setup added to /home/$USERNAME/.bashrc" + else + echo "ROS2 foxy environment is already set in /home/$USERNAME/.bashrc" + fi +elif [ $Ubuntu_version = "22.04" ]; then + if ! grep -q "source /opt/ros/humble/setup.bash" /home/$USERNAME/.bashrc; then + + echo "# ROS2 humble Environment Setting" | sudo tee -a /home/$USERNAME/.bashrc + echo "source /opt/ros/humble/setup.bash" | sudo tee -a /home/$USERNAME/.bashrc + echo "ROS2 humble environment setup added to /home/$USERNAME/.bashrc" + else + echo "ROS2 humble environment is already set in /home/$USERNAME/.bashrc" + fi +fi + +source /home/$USERNAME/.bashrc + +# Initialize rosdepc by fishros under BSD License +# https://pypi.org/project/rosdepc/#files +sudo pip install rosdep +sudo pip install rosdepc +# sudo pip install -i https://pypi.tuna.tsinghua.edu.cn/simple -U rosdep +# Init & update rosdep +sudo rosdepc init > /dev/null +#sudo rosdep fix-permissions +# su -l $USERNAME -c 'rosdepc update' > /dev/null +echo "rosdepc init completed!" + +# System update again +sudo apt-get update +sudo apt-get dist-upgrade -y + +# Verifying ROS2 installation +clear + +source /home/$USERNAME/.bashrc +# Define the variables to be printed +TEXT1="ROS2 installation completed!" +TEXT2="Please open a new terminal and run demo to verify the installation:" + +# Define the colors +RED='\033[0;31m' +BLUE='\033[0;34m' +GREEN='\033[1;32m' +NC='\033[0m' + +# Calculate the center of the terminal window +TERMINAL_WIDTH=$(tput cols) +TEXT1_PADDING=$((($TERMINAL_WIDTH-${#TEXT1})/2)) +TEXT2_PADDING=$((($TERMINAL_WIDTH-${#TEXT2})/2)) +TEXT3_PADDING=$((($TERMINAL_WIDTH-${#TEXT3})/2)) + +# Print the text in the center of the screen in the desired colors +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo -e "${GREEN}$(printf '%*s' $TEXT1_PADDING)${TEXT1} ${NC}" +echo -e "${NC}$(printf '%*s' $TEXT2_PADDING)${TEXT2} ${NC}" +echo -e "${RED}$(printf '%*s' $TEXT3_PADDING)${TEXT3} ${NC}" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/src/lib_install.sh b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/src/lib_install.sh new file mode 100644 index 0000000..db732b9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_install/src/lib_install.sh @@ -0,0 +1,74 @@ +#!/bin/bash +# Version: 1.4 +# Date: 2023-06-19 +# Author: Herman Ye @Realman Robotics +# Warning: This script is ONLY for ROS2 Humble in ubuntu 20.04 +# set -x +set -e + + + +# UBUNTU CONFIGURATION BEGINS HERE + +# Check if script is run as root (sudo) +if [ "$(id -u)" != "0" ]; then + echo "This script must be run with sudo privileges. for example: sudo bash ros2_humble_install.sh" + read -p "Press any key to exit..." + exit 1 +fi + + +if [ $(uname -m) = "x86_64" ]; then + sudo rm libRM_Service.so* + sudo tar -jxvf linux_x86_service_release* + + if [ -f "/usr/local/lib/linux_x86_service_release*" ];then + echo "find file" + sudo rm /usr/local/lib/libRM_Service.so* + sudo rm /usr/local/lib/linux_x86_service_release* + fi + sudo cp linux_x86_service_release* /usr/local/lib + cd /usr/local/lib + sudo tar -jxvf /usr/local/lib/linux_x86_service_release* +else + sudo rm libRM_Service.so* + sudo tar -jxvf linux_arm_service_release* + + if [ -f "/usr/local/lib/linux_arm_service_release*" ];then + sudo rm /usr/local/lib/libRM_Service.so* + sudo rm /usr/local/lib/inux_arm_service_release* + fi + sudo cp linux_arm_service_release* /usr/local/lib + cd /usr/local/lib + sudo tar -jxvf /usr/local/lib/linux_arm_service_release* +fi +if ! grep -q "/usr/local/lib" /etc/ld.so.conf; then + echo "/usr/local/lib" | sudo tee -a /etc/ld.so.conf +else + echo "/usr/local/lib is already set in /etc/ld.so.conf" +fi +sudo /sbin/ldconfig +cd ~ +TEXT1="Lib installation completed!" +TEXT1_PADDING=$((($TERMINAL_WIDTH-${#TEXT1})/2)) +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo -e "${GREEN}$(printf '%*s' $TEXT1_PADDING)${TEXT1} ${NC}" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" +echo "" diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README.md new file mode 100644 index 0000000..e960e2c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README.md @@ -0,0 +1,327 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_moveit2_config/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_moveit2_config/README.md) + +
+ +
+ +# RealMan Robotic Arm rm_moveit2_config User Manual V1.4 + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History: + +|No. | Date | Comment | +| :---: | :----: | :---: | +|V1.0 | 2/19/2024 | Draft | +|V1.1 | 7/3 /2024 | Amend(Add GEN72 adapter files) | +|V1.2 | 10/9/2024 | Amend(Add ECO63 adapter files) | +|V1.3 | 25/12/2024 | Amend(Add 63, 65, 75, ECO65 six-axis force adapter files and 63, 65, 75, ECO63, ECO65 integrated six-axis force adapter files) | +|V1.4 |2025-4-3 | Amend(AddGen72_IIadapter files) | + +
+ +## Content +* 1.[rm_moveit2_config Description](#rm_moveit2_config_Description) +* 2.[rm_moveit2_config Use](#rm_moveit2_config_Use) +* 2.1[moveit2 Controlling Virtual Robotic Arm](#moveit2_Controlling_Virtual_Robotic_Arm) +* 2.2[moveit2 Controlling Real Robotic Arm](#moveit2_Controlling_Real_Robotic_Arm) +* 3.[rm_moveit2_config Architecture Description](#rm_moveit2_config_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4.[rm_moveit2_config Topic Description](#rm_moveit2_config_Topic_Description) + + +  +## rm_moveit2_config_Description +rm_moveit2_config folder is a function package for realizing the moveit2 control of a real robotic arm. The package is mainly used to call the official moveit2 framework and generate the configuration and launch file of moveit2 suitable for our robotic arm combined with the URDF of the robotic arm. Through this package, we can realize the moveit2 control of the virtual robotic arm and control of the real robotic arm. This package is introduced in detail in the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you: +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +Source code address: https://github.com/RealManRobot/ros2_rm_robot.git。 +## rm_moveit2_config_Use +### moveit2_Controlling_Virtual_Robotic_Arm +First, after configuring the environment and completing the connection, we can directly launch the node through the following command. +``` +rm@rm-desktop:~$ ros2 launch rm__config demo.launch.py +``` +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm__config demo_6f.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm__config demo_6fb.launch.py +``` +In practice, the above needs to be replaced by the actual model of the robotic arm. The available models of the robotic arm are 65, 63, eco65, eco63, 75, and gen72、gen72_II. +For example, the launch command of 65 robotic arm: +``` +rm@rm-desktop:~$ ros2 launch rm_65_config demo.launch.py +``` +The following screen appears in the interface after successful node startup. +![image](doc/rm_moveit2_config1.png) +Next, we can make the robotic arm reach the target position by dragging the control ball and then clicking Plan Execution. +![image](doc/rm_moveit2_config2.png) +Execute the plan. +![image](doc/rm_moveit2_config3.png) +### moveit2_Controlling_Real_Robotic_Arm +There are relatively more control commands required to control a real robotic arm, and the following is a detailed control method. +First, run the chassis driver node. +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +Next, run the rm_description package file. +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__display.launch.py +``` +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6f_display.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6fb_display.launch.py +``` +Then, run the relevant nodes of the intermediate package rm_control. +``` +rm@rm-desktop:~$ ros2 launch rm_control rm__control.launch.py +``` +Finally, launch the moveit2 node that controls the real robotic arm. +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo.launch.py +``` +The command to start the six-axis force version of the manipulator is (note: eco63 is not available): +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo_6f.launch.py +``` +The command to start the integrated six-axis force version of the manipulator is : +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo_6fb.launch.py +``` +Note that the above commands need to replace with the corresponding robotic arm model, which can be selected as 65, 63, eco65, eco63, 75, and gen72、gen72_II. +After completing the above operations, the following interface appears, and we can control the movement of the robotic arm by dragging the control ball. +![image](doc/rm_moveit2_config4.png) +## rm_moveit2_config_Architecture_Description +### Overview_of_package_files +The current rm_moveit2_config package is composed of the following files. +``` +├── doc +│ ├── rm_moveit2_config1.png +│ ├── rm_moveit2_config2.png +│ ├── rm_moveit2_config3.png +│ ├── rm_moveit2_config4.png +│ ├── rm_moveit2_config5.png +│ ├── rm_moveit2_config6.png +│ ├── rm_moveit2_config7.png +│ ├── rm_moveit2_config8.png +│ └── rm_moveit2_config9.png +├── README_CN.md +├── README.md +├── rm_63_config #63 robotic arm moveit2 package +│ ├── CMakeLists.txt #63 robotic arm moveit2 package compilation rules +│ ├── config #63 robotic arm moveit2 package parameter folder +│ │ ├── initial_positions.yaml #63 robotic arm moveit2 initial position +│ │ ├── joint_limits.yaml #63 robotic arm joint limits +│ │ ├── kinematics.yaml #63 robotic arm kinematics parameters +│ │ ├── moveit_controllers.yaml #63 robotic arm moveit2 controller +│ │ ├── moveit.rviz #63 robotic arm rviz2 display configuration file +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rml_63_description.ros2_control.xacro #63 robotic arm xacro description file +│ │ ├── rml_63_description.srdf #63 robotic arm moveit2 control configuration file +│ │ ├── rml_63_description.urdf.xacro #63 robotic arm xacro description file +│ │ ├── rml_63.urdf.xacro +│ │ └── ros2_controllers.yaml #63 robotic arm move controller +│ ├── launch +│ │ ├── demo_6f.launch.py #63 six-axis force virtual robotic arm moveit2 launch file +│ │ ├── demo_6fb.launch.py #63 integrated six-axis force virtual robotic arm moveit2 launch file +│ │ ├── demo.launch.py #63 virtual robotic arm moveit2 launch file +│ │ ├── gazebo_moveit_demo_6f.launch.py #63 six-axis force simulation robotic arm moveit2 launch file +│ │ ├── gazebo_moveit_demo_6fb.launch.py #63 integrated six-axis force simulation robotic arm moveit2 launch file +│ │ ├── gazebo_moveit_demo.launch.py #63 simulation robotic arm moveit2 launch file +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py #63 six-axis force real robotic arm moveit2 launch file +│ │ ├── real_moveit_demo_6fb.launch.py #63 integrated six-axis force real robotic arm moveit2 launch file +│ │ ├── real_moveit_demo.launch.py #63 real robotic arm moveit2 launch file +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_65_config #65 robotic arm moveit2 package (file explanation reference 63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_65_description.ros2_control.xacro +│ │ ├── rm_65_description.srdf +│ │ ├── rm_65_description.urdf.xacro +│ │ ├── rm_65.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_75_config #75 robotic arm moveit2 package (file explanation reference 63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_75_description.ros2_control.xacro +│ │ ├── rm_75_description.srdf +│ │ ├── rm_75_description.urdf.xacro +│ │ ├── rm_75.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_eco65_config #eco65 robotic arm moveit2 package (file explanation reference 63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_eco65_description.ros2_control.xacro +│ │ ├── rm_eco65_description.srdf +│ │ ├── rm_eco65_description.urdf.xacro +│ │ ├── rm_eco65.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_eco63_config #eco63 robotic arm moveit2 package (file explanation reference 63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_eco63_description.ros2_control.xacro +│ │ ├── rm_eco63_description.srdf +│ │ ├── rm_eco63_description.urdf.xacro +│ │ ├── rm_eco63.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +└── rm_gen72_config #gen72 robotic arm moveit2 package (file explanation reference 63) + ├── CMakeLists.txt + ├── config + │ ├── initial_positions.yaml + │ ├── joint_limits.yaml + │ ├── kinematics.yaml + │ ├── moveit_controllers.yaml + │ ├── moveit.rviz + │ ├── pilz_cartesian_limits.yaml + │ ├── rm_gen72_description.ros2_control.xacro + │ ├── rm_gen72_description.srdf + │ ├── rm_gen72_description.urdf.xacro + │ ├── rm_gen72_II_description.urdf.xacro + │ └── ros2_controllers.yaml + ├── launch + │ ├── demo.launch.py + │ ├── demo_II.launch.py + │ ├── gazebo_moveit_demo.launch.py + │ ├── gazebo_moveit_demo_II.launch.py + │ ├── move_group.launch.py + │ ├── moveit_rviz.launch.py + │ ├── real_moveit_demo.launch.py + │ ├── real_moveit_demo_II.launch.py + │ ├── rsp.launch.py + │ ├── setup_assistant.launch.py + │ ├── spawn_controllers.launch.py + │ ├── static_virtual_joint_tfs.launch.py + │ └── warehouse_db.launch.py + └── package.xml +``` +## rm_moveit2_config_Topic_Description +About the topic description of moveit2, to make its topic structure clearer, we will view and explain it here in the form of a data flow graph of node topics. +After launching the node that controls the real robot as above, we can run the following command to view the docking situation of the current topic. +``` +rm@rm-desktop:~$ ros2 run rqt_graph rqt_graph +``` +The interface displays as follows after successful running. +![image](doc/rm_moveit2_config5.png) +The figure reflects the topic communication relationship between the currently running nodes and nodes. Firstly, view the /rm_driver node, which subscribes and publishes the following topics when moveit2 is running. +![image](doc/rm_moveit2_config6.png) +![image](doc/rm_moveit2_config7.png) +As we can see from the figure, the /joint_states topic published by rm_driver is continuously subscribed by the /robot_state_publiser node and the /move_group_private node. / robot_state_publiser receives /joint_states to continuously publish TF transformations between joints; /move_group_private is the relevant node of moveit2, which also needs to obtain the current joint state information of the robotic arm in real-time during planning, so it also subscribes to this topic. +As we can see from the figure, rm_driver also subscribes to the topic of /rm_driver/movej_canfd_cmd of rm_control, which is the topic of the transmission function of the robotic arm. Through this topic, rm_control publishes the planned joint nodes to rm_driver node to control the movement of the robotic arm. +![image](doc/rm_moveit2_config8.png) +rm_control is the bridge of communication between rm_driver and moveit2. It communicates with /moveit_simple_controller_manager through the action of /rm_group_controller/follow_joint_trajectory to obtain the planned points and perform interpolation operations. Give interpolated data to rm_driver through transmission. +![image](doc/rm_moveit2_config9.png) +The nodes involved in moveit2 include move_group, move_group_private and moveit_simple_controller_manager. The main function is to realize the movement planning of the robotic arm and to display the planning information and other data in rviz. On the other hand, the planning data need to be passed to rm_control for further subdivision. diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README_CN.md new file mode 100644 index 0000000..b65bf4d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/README_CN.md @@ -0,0 +1,324 @@ +
+ +[简体中文](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_moveit2_config/README_CN.md)|[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_moveit2_config/README.md) + +
+ +
+ +# 睿尔曼机器人rm_moveit2_config使用说明书V1.4 + +睿尔曼智能科技(北京)有限公司 +文件修订记录: + +| 版本号| 时间 | 备注 | +| :---: | :-----: | :---: | +|V1.0 |2024-2-19 |拟制 | +|V1.1 |2024-7-8 |修订(添加GEN72适配) | +|V1.2 |2024-9-10 |修订(添加ECO63适配) | +|V1.3 |2024-12-25 |修订(添加了63、65、75、ECO65的六维力适配文件,以及63、65、75、ECO63、ECO65的一体化六维力适配文件) | +|V1.4 |2025-4-3 |修订(添加了Gen72_II型适配文件) | + +
+ +## 目录 +* 1.[rm_moveit2_config说明](#rm_moveit2_config说明) +* 2.[rm_moveit2_config使用](#rm_moveit2_config使用) +* 2.1[moveit2控制虚拟机械臂](#moveit2控制虚拟机械臂) +* 2.2[moveit2控制真实机械臂](#moveit2控制真实机械臂) +* 3.[rm_moveit2_config架构说明](#rm_moveit2_config架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4.[rm_moveit2_config话题说明](#rm_moveit2_config话题说明) + +## rm_moveit2_config说明 +rm_moveit2_config文件夹为实现moveit2控制真实机械臂的功能包,该功能包的主要作用为调用官方的moveit2框架,结合我们机械臂本身的URDF生成适配于我们机械臂的moveit2的配置和启动文件,通过该功能包我们可以实现moveit2控制虚拟机械臂和控制真实机械臂。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用。 +## rm_moveit2_config使用 +### moveit2控制虚拟机械臂 +首先配置好环境完成连接后我们可以通过以下命令直接启动节点。 +``` +rm@rm-desktop:~$ ros2 launch rm__config demo.launch.py +``` +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm__config demo_6f.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm__config demo_6fb.launch.py +``` +在实际使用时需要将以上的更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。 +例如65机械臂的启动命令: +``` +rm@rm-desktop:~$ ros2 launch rm_65_config demo.launch.py +``` +节点启动成功后,将显示以下画面。 +![image](doc/rm_moveit2_config1.png) +接下来我们可以通过拖动控制球使机械臂到达目标位置,然后点击规划执行。 +![image](doc/rm_moveit2_config2.png) +规划执行。 +![image](doc/rm_moveit2_config3.png) +### moveit2控制真实机械臂 +控制真实机械臂需要的控制指令相对较多一些,如下为详细的控制方式。 +首先运行底盘驱动节点。 +``` +rm@rm-desktop:~$ ros2 launch rm_driver rm__driver.launch.py +``` +接下来需要运行rm_description功能包文件。 +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__display.launch.py +``` +注意: +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6f_display.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm_description rm__6fb_display.launch.py +``` +之后需要运行中间功能包rm_control的相关节点。 +``` +rm@rm-desktop:~$ ros2 launch rm_control rm__control.launch.py +``` +最终需要启动控制真实机械臂的moveit2节点。 +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo.launch.py +``` +启动六维力版本机械臂的命令为(注意:eco63不可用): +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo_6f.launch.py +``` +启动一体化六维力版本机械臂的命令为: +``` +rm@rm-desktop:~$ ros2 launch rm__config real_moveit_demo_6fb.launch.py +``` +注意以上指令均需要将更换为对应的机械臂型号,可选择的型号有65、63、eco65、eco63、75、gen72、gen72_II。 +完成以上操作后将会出现以下界面,我们可以通过拖动控制球的方式控制机械臂运动。 +![image](doc/rm_moveit2_config4.png) +## rm_moveit2_config架构说明 +### 功能包文件总览 +当前rm_moveit2_config功能包的文件构成如下。 +``` +├── doc +│ ├── rm_moveit2_config1.png +│ ├── rm_moveit2_config2.png +│ ├── rm_moveit2_config3.png +│ ├── rm_moveit2_config4.png +│ ├── rm_moveit2_config5.png +│ ├── rm_moveit2_config6.png +│ ├── rm_moveit2_config7.png +│ ├── rm_moveit2_config8.png +│ └── rm_moveit2_config9.png +├── README_CN.md +├── README.md +├── rm_63_config #63机械臂moveit2功能包 +│ ├── CMakeLists.txt #63机械臂moveit2功能包编译规则 +│ ├── config #63机械臂moveit2功能包参数文件夹 +│ │ ├── initial_positions.yaml #63机械臂moveit2初始化位姿 +│ │ ├── joint_limits.yaml #63机械臂关节限制 +│ │ ├── kinematics.yaml #63机械臂运动学参数 +│ │ ├── moveit_controllers.yaml #63机械臂moveit2控制器 +│ │ ├── moveit.rviz #63机械臂rviz2显示配置文件 +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rml_63_description.ros2_control.xacro #63机械臂xacro描述文件 +│ │ ├── rml_63_description.srdf #63机械臂moveit2控制配置文件 +│ │ ├── rml_63_description.urdf.xacro #63机械臂xacro描述文件 +│ │ ├── rml_63.urdf.xacro +│ │ └── ros2_controllers.yaml #63机械臂运动控制器 +│ ├── launch +│ │ ├── demo_6f.launch.py #63六维力虚拟机械臂moveit2启动文件 +│ │ ├── demo_6fb.launch.py #63一体化六维力虚拟机械臂moveit2启动文件 +│ │ ├── demo.launch.py #63虚拟机械臂moveit2启动文件 +│ │ ├── gazebo_moveit_demo_6f.launch.py #63六维力仿真机械臂moveit2启动文件 +│ │ ├── gazebo_moveit_demo_6fb.launch.py #63一体化六维力仿真机械臂moveit2启动文件 +│ │ ├── gazebo_moveit_demo.launch.py #63仿真机械臂moveit2启动文件 +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py #63六维力真实机械臂moveit2启动文件 +│ │ ├── real_moveit_demo_6fb.launch.py #63一体化六维力真实机械臂moveit2启动文件 +│ │ ├── real_moveit_demo.launch.py #63真实机械臂moveit2启动文件 +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_65_config #65机械臂moveit2功能包(文件解释参考63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_65_description.ros2_control.xacro +│ │ ├── rm_65_description.srdf +│ │ ├── rm_65_description.urdf.xacro +│ │ ├── rm_65.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_75_config #75机械臂moveit2功能包(文件解释参考63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_75_description.ros2_control.xacro +│ │ ├── rm_75_description.srdf +│ │ ├── rm_75_description.urdf.xacro +│ │ ├── rm_75.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_eco65_config #eco65机械臂moveit2功能包(文件解释参考63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_eco65_description.ros2_control.xacro +│ │ ├── rm_eco65_description.srdf +│ │ ├── rm_eco65_description.urdf.xacro +│ │ ├── rm_eco65.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6f.launch.py +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6f.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6f.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +├── rm_eco63_config #eco63机械臂moveit2功能包(文件解释参考63) +│ ├── CMakeLists.txt +│ ├── config +│ │ ├── initial_positions.yaml +│ │ ├── joint_limits.yaml +│ │ ├── kinematics.yaml +│ │ ├── moveit_controllers.yaml +│ │ ├── moveit.rviz +│ │ ├── pilz_cartesian_limits.yaml +│ │ ├── rm_eco63_description.ros2_control.xacro +│ │ ├── rm_eco63_description.srdf +│ │ ├── rm_eco63_description.urdf.xacro +│ │ ├── rm_eco63.urdf.xacro +│ │ └── ros2_controllers.yaml +│ ├── launch +│ │ ├── demo_6fb.launch.py +│ │ ├── demo.launch.py +│ │ ├── gazebo_moveit_demo_6fb.launch.py +│ │ ├── gazebo_moveit_demo.launch.py +│ │ ├── move_group.launch.py +│ │ ├── moveit_rviz.launch.py +│ │ ├── real_moveit_demo_6fb.launch.py +│ │ ├── real_moveit_demo.launch.py +│ │ ├── rsp.launch.py +│ │ ├── setup_assistant.launch.py +│ │ ├── spawn_controllers.launch.py +│ │ ├── static_virtual_joint_tfs.launch.py +│ │ └── warehouse_db.launch.py +│ └── package.xml +└── rm_gen72_config #gen72机械臂moveit2功能包(文件解释参考63) + ├── CMakeLists.txt + ├── config + │ ├── initial_positions.yaml + │ ├── joint_limits.yaml + │ ├── kinematics.yaml + │ ├── moveit_controllers.yaml + │ ├── moveit.rviz + │ ├── pilz_cartesian_limits.yaml + │ ├── rm_gen72_description.ros2_control.xacro + │ ├── rm_gen72_description.srdf + │ ├── rm_gen72_description.urdf.xacro + │ ├── rm_gen72_II_description.urdf.xacro + │ └── ros2_controllers.yaml + ├── launch + │ ├── demo.launch.py + │ ├── demo_II.launch.py + │ ├── gazebo_moveit_demo.launch.py + │ ├── gazebo_moveit_demo_II.launch.py + │ ├── move_group.launch.py + │ ├── moveit_rviz.launch.py + │ ├── real_moveit_demo.launch.py + │ ├── real_moveit_demo_II.launch.py + │ ├── rsp.launch.py + │ ├── setup_assistant.launch.py + │ ├── spawn_controllers.launch.py + │ ├── static_virtual_joint_tfs.launch.py + │ └── warehouse_db.launch.py + └── package.xml +``` +## rm_moveit2_config话题说明 +关于moveit2的话题说明,为使其话题结构更加清晰明白在这里以节点话题的数据流图的方式进行查看和讲解。 +在启动如上控制真实机器人的节点后可以运行如下指令查看当前话题的对接情况。 +``` +rm@rm-desktop:~$ ros2 run rqt_graph rqt_graph +``` +运行成功后界面将显示如下画面。 +![image](doc/rm_moveit2_config5.png) +该图反应了当前运行的节点与节点之间的话题通信关系,首先查看/rm_driver节点,该节点在moveit2运行时订阅和发布的话题如下。 +![image](doc/rm_moveit2_config6.png) +![image](doc/rm_moveit2_config7.png) +由图可知,rm_driver发布的/joint_states话题在持续被/robot_state_publiser节点和/move_group_private节点订阅。/robot_state_publiser接收/joint_states是为了持续发布关节间的TF变换;/move_group_private是moveit2的相关节点,moveit2在规划时也需要实时获取当前机械臂的关节状态信息,所以也订阅了该话题。 +由图可知rm_driver还订阅了rm_control的/rm_driver/movej_canfd_cmd话题,该话题是机械臂透传功能的话题,通过该话题rm_control将规划的关节点位发布给rm_driver节点控制机械臂进行运动。 +![image](doc/rm_moveit2_config8.png) +rm_control为rm_driver与moveit2之间通信的桥梁,其通过/rm_group_controller/follow_joint_trajectory动作与/moveit_simple_controller_manager进行通信,获取规划点,并进行插值运算,将插值之后的数据通过透传的方式给到rm_driver。 +![image](doc/rm_moveit2_config9.png) +Moveit2本身涉及的节点有move_group、move_group_private、moveit_simple_controller_manager,它们的主要作用为实现机械臂的运动规划,并将规划信息等数据显示在rviz中,另一方面还需要将规划数据传递到rm_control端,进行进一步细分。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config1.png new file mode 100644 index 0000000..56c39df Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config1.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config2.png new file mode 100644 index 0000000..e371483 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config2.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config3.png new file mode 100644 index 0000000..1e66e17 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config3.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config4.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config4.png new file mode 100644 index 0000000..164c05c Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config4.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config5.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config5.png new file mode 100644 index 0000000..2a1d704 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config5.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config6.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config6.png new file mode 100644 index 0000000..e346200 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config6.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config7.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config7.png new file mode 100644 index 0000000..fd93260 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config7.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config8.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config8.png new file mode 100644 index 0000000..3476b03 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config8.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config9.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config9.png new file mode 100644 index 0000000..517e150 Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/doc/rm_moveit2_config9.png differ diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/.setup_assistant new file mode 100644 index 0000000..adb8a61 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: rml_63_description + relative_path: urdf/rml_63_description.urdf + srdf: + relative_path: config/rml_63_description.srdf + package_settings: + author_name: Kaola + author_email: Kaola@qq.com + generated_timestamp: 1700029109 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/CMakeLists.txt new file mode 100644 index 0000000..a6f0bfd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_63_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/initial_positions.yaml new file mode 100644 index 0000000..ad1e9e8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for rml_63_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/joint_limits.yaml new file mode 100644 index 0000000..476ad64 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/kinematics.yaml new file mode 100644 index 0000000..ae2a6d5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit.rviz new file mode 100644 index 0000000..41b56e8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..630bb14 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/moveit_controllers.yaml @@ -0,0 +1,19 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6++-+ \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..c7c7205 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_6fb_description.urdf.xacro new file mode 100644 index 0000000..e6e1b37 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_6fb_description.urdf.xacro @@ -0,0 +1,18 @@ + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.ros2_control.xacro new file mode 100644 index 0000000..4612850 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.ros2_control.xacro @@ -0,0 +1,56 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.srdf new file mode 100644 index 0000000..7b2ed14 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.srdf @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.urdf.xacro new file mode 100644 index 0000000..9dbb5e4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/rml_63_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..eed1e07 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo.launch.py new file mode 100644 index 0000000..4d06778 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6f.launch.py new file mode 100644 index 0000000..facfd5f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6f.launch.py @@ -0,0 +1,295 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + # .robot_description_semantic(file_path="config/rm_65_description.srdf") + # .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6fb.launch.py new file mode 100644 index 0000000..32a15bd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/demo_6fb.launch.py @@ -0,0 +1,295 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + # .robot_description_semantic(file_path="config/rm_65_description.srdf") + # .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..c0ab696 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6f.launch.py new file mode 100644 index 0000000..9237942 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6f.launch.py @@ -0,0 +1,118 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..f2c6d9d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/gazebo_moveit_demo_6fb.launch.py @@ -0,0 +1,118 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/move_group.launch.py new file mode 100644 index 0000000..60a9eea --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..c454632 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..e65e97b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,123 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6f.launch.py new file mode 100644 index 0000000..a6ad577 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6f.launch.py @@ -0,0 +1,128 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..675e14d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/real_moveit_demo_6fb.launch.py @@ -0,0 +1,128 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config") + .robot_description(file_path="config/rml_63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/rsp.launch.py new file mode 100644 index 0000000..0df19d4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..8d7cfc5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..a988814 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..0b64c61 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..34234aa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rml_63_description", package_name="rm_63_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/package.xml new file mode 100644 index 0000000..c4dcbc7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_63_config/package.xml @@ -0,0 +1,52 @@ + + + + rm_63_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rml_63_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/.setup_assistant new file mode 100644 index 0000000..0ea89df --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: rm_description + relative_path: urdf/rm_65.urdf + srdf: + relative_path: config/rm_65_description.srdf + package_settings: + author_name: Kaola + author_email: Kaola@qq.com + generated_timestamp: 1699451912 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/CMakeLists.txt new file mode 100644 index 0000000..2813049 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_65_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/initial_positions.yaml new file mode 100644 index 0000000..0942a29 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for rm_65_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/joint_limits.yaml new file mode 100644 index 0000000..476ad64 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/kinematics.yaml new file mode 100644 index 0000000..ae2a6d5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit.rviz new file mode 100644 index 0000000..41b56e8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..603c9db --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/moveit_controllers.yaml @@ -0,0 +1,19 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..c7c7205 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_6fb_description.urdf.xacro new file mode 100644 index 0000000..baa42a0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_6fb_description.urdf.xacro @@ -0,0 +1,19 @@ + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.ros2_control.xacro new file mode 100644 index 0000000..04ba121 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.ros2_control.xacro @@ -0,0 +1,56 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.srdf new file mode 100644 index 0000000..bd96626 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.srdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.urdf.xacro new file mode 100644 index 0000000..322edb8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/rm_65_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..eed1e07 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo.launch.py new file mode 100644 index 0000000..c69dace --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6f.launch.py new file mode 100644 index 0000000..ff65f54 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6f.launch.py @@ -0,0 +1,292 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch copy.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch copy.py new file mode 100644 index 0000000..e61c517 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch copy.py @@ -0,0 +1,145 @@ +# from moveit_configs_utils import MoveItConfigsBuilder +# from moveit_configs_utils.launches import generate_demo_launch + + +# def generate_launch_description(): +# moveit_config = ( +# MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") +# .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro").to_moveit_configs() +# ) +# return generate_demo_launch(moveit_config) +import os +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from ament_index_python.packages import get_package_share_directory +from moveit_configs_utils import MoveItConfigsBuilder + + +def generate_launch_description(): + + # Command-line arguments + db_arg = DeclareLaunchArgument( + "db", default_value="False", description="Database flag" + ) + + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro") + .robot_description_semantic(file_path="config/rm_65_description.srdf") + .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + + # Start the actual move_group node/action server + run_move_group_node = Node( + package="moveit_ros_move_group", + executable="move_group", + output="screen", + parameters=[moveit_config.to_dict()], + ) + + # RViz + rviz_base = os.path.join( + get_package_share_directory("rm_65_config"), "config" + ) + rviz_full_config = os.path.join(rviz_base, "moveit.rviz") + + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_full_config], + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ], + ) + + # Static TF + static_tf = Node( + package="tf2_ros", + executable="static_transform_publisher", + name="static_transform_publisher", + output="log", + arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "base_link"], + ) + + # Publish TF + robot_state_publisher = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name="robot_state_publisher", + output="both", + parameters=[moveit_config.robot_description], + ) + + # ros2_control using FakeSystem as hardware + ros2_controllers_path = os.path.join( + get_package_share_directory("rm_65_config"), + "config", + "ros2_controllers.yaml", + ) + ros2_control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ros2_controllers_path], + remappings=[ + ("/controller_manager/robot_description", "/robot_description"), + ], + output="both", + ) + + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=[ + "joint_state_broadcaster", + "--controller-manager", + "/controller_manager", + ], + ) + + rm_group_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=[ + "rm_group_controller", + "--controller-manager", + "/controller_manager", + ], + ) + + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + mongodb_server_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + + return LaunchDescription( + [ + db_arg, + rviz_node, + static_tf, + robot_state_publisher, + run_move_group_node, + ros2_control_node, + mongodb_server_node, + joint_state_broadcaster_spawner, + rm_group_controller_spawner, + ] + ) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch.py new file mode 100644 index 0000000..66c05bb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/demo_6fb.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..2e3c7d3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6f.launch.py new file mode 100644 index 0000000..616fbd2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6f.launch.py @@ -0,0 +1,120 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..616fbd2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/gazebo_moveit_demo_6fb.launch.py @@ -0,0 +1,120 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/move_group.launch.py new file mode 100644 index 0000000..50f57bc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..2637238 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..776b85f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,123 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6f.launch.py new file mode 100644 index 0000000..2302b07 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6f.launch.py @@ -0,0 +1,130 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + # .robot_description_semantic(file_path="config/rm_65_description.srdf") + # .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..623f72d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/real_moveit_demo_6fb.launch.py @@ -0,0 +1,130 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config") + .robot_description(file_path="config/rm_65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + # .robot_description_semantic(file_path="config/rm_65_description.srdf") + # .trajectory_execution(file_path="config/moveit_controllers.yaml") + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/rsp.launch.py new file mode 100644 index 0000000..734e65e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..e1381b0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..80cff68 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..a7a0067 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..12bfef3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_65_description", package_name="rm_65_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/package.xml new file mode 100644 index 0000000..436b95e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_65_config/package.xml @@ -0,0 +1,52 @@ + + + + rm_65_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_65_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_65_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/.setup_assistant new file mode 100644 index 0000000..ee77fcf --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: rm_description + relative_path: urdf/rm_75.urdf + srdf: + relative_path: config/rm_75_description.srdf + package_settings: + author_name: Kaola + author_email: Kaola@qq.com + generated_timestamp: 1700462725 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/CMakeLists.txt new file mode 100644 index 0000000..eb1abc0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_75_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/initial_positions.yaml new file mode 100644 index 0000000..61bca48 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/initial_positions.yaml @@ -0,0 +1,10 @@ +# Default initial positions for rm_75_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 + joint7: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/joint_limits.yaml new file mode 100644 index 0000000..77dba93 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/joint_limits.yaml @@ -0,0 +1,45 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint7: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/kinematics.yaml new file mode 100644 index 0000000..ae2a6d5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit.rviz new file mode 100644 index 0000000..41b56e8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..30cf596 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/moveit_controllers.yaml @@ -0,0 +1,20 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + - joint7 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..c7c7205 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_6fb_description.urdf.xacro new file mode 100644 index 0000000..e057d04 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_6fb_description.urdf.xacro @@ -0,0 +1,19 @@ + + + + + + + + + link7_type:=$(arg link7_type) + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.ros2_control.xacro new file mode 100644 index 0000000..bc53ed3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.ros2_control.xacro @@ -0,0 +1,63 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + ${initial_positions['joint7']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.srdf new file mode 100644 index 0000000..e211209 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.srdf @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.urdf.xacro new file mode 100644 index 0000000..17094da --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/rm_75_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..e3c1b64 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/config/ros2_controllers.yaml @@ -0,0 +1,27 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + - joint7 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo.launch.py new file mode 100644 index 0000000..576d01c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6f.launch.py new file mode 100644 index 0000000..ed70edc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6f.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6f"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6fb.launch.py new file mode 100644 index 0000000..c6338f7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/demo_6fb.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..7cbfe10 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6f.launch.py new file mode 100644 index 0000000..32967df --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6f.launch.py @@ -0,0 +1,119 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6f"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..58a078a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/gazebo_moveit_demo_6fb.launch.py @@ -0,0 +1,119 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/move_group.launch.py new file mode 100644 index 0000000..c5a5ec2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..54294e4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..6202167 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,122 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + "monitor_dynamics": False, + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6f.launch.py new file mode 100644 index 0000000..aa09163 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6f.launch.py @@ -0,0 +1,127 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6f"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + "monitor_dynamics": False, + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..3eec8b1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/real_moveit_demo_6fb.launch.py @@ -0,0 +1,127 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config") + .robot_description(file_path="config/rm_75_6fb_description.urdf.xacro", mappings={"link7_type": "Link7_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + "monitor_dynamics": False, + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/rsp.launch.py new file mode 100644 index 0000000..ef561df --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..b598151 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..1937bf7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..5ca2d10 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..679ee4d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_75_description", package_name="rm_75_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/package.xml new file mode 100644 index 0000000..4eca0cc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_75_config/package.xml @@ -0,0 +1,52 @@ + + + + rm_75_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_75_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/.setup_assistant new file mode 100644 index 0000000..e459c6c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: rm_eco63_description + relative_path: urdf/rm_eco63.urdf.xacro + srdf: + relative_path: config/rm_eco63_description.srdf + package_settings: + author_name: Kaola + author_email: Kaola@qq.com + generated_timestamp: 1699967197 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/CMakeLists.txt new file mode 100644 index 0000000..a7facbc --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_eco63_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/initial_positions.yaml new file mode 100644 index 0000000..346d588 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for rm_eco63_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/joint_limits.yaml new file mode 100644 index 0000000..476ad64 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/kinematics.yaml new file mode 100644 index 0000000..ae2a6d5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit.rviz new file mode 100644 index 0000000..41b56e8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..603c9db --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/moveit_controllers.yaml @@ -0,0 +1,19 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..c7c7205 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_6fb_description.urdf.xacro new file mode 100644 index 0000000..bd22895 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_6fb_description.urdf.xacro @@ -0,0 +1,17 @@ + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.ros2_control.xacro new file mode 100644 index 0000000..722c658 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.ros2_control.xacro @@ -0,0 +1,56 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.srdf new file mode 100644 index 0000000..88855bb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.srdf @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.urdf.xacro new file mode 100644 index 0000000..cce5131 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/rm_eco63_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..eed1e07 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo.launch.py new file mode 100644 index 0000000..bd7dcc6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo_6fb.launch.py new file mode 100644 index 0000000..4552476 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/demo_6fb.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config") + .robot_description(file_path="config/rm_eco63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..b229696 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..c435d58 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/gazebo_moveit_demo_6fb.launch.py @@ -0,0 +1,118 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config") + .robot_description(file_path="config/rm_eco63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/move_group.launch.py new file mode 100644 index 0000000..c9d11f5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..99c8b21 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..74290eb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,123 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from launch_ros.substitutions import FindPackageShare + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..da03a5e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/real_moveit_demo_6fb.launch.py @@ -0,0 +1,128 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from launch_ros.substitutions import FindPackageShare + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config") + .robot_description(file_path="config/rm_eco63_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/rsp.launch.py new file mode 100644 index 0000000..dc2bedb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..aa7c36a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..da858b1 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..e383576 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..46e6ecb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco63_description", package_name="rm_eco63_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/package.xml new file mode 100644 index 0000000..1fe2851 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco63_config/package.xml @@ -0,0 +1,52 @@ + + + + rm_eco63_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_eco63_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/.setup_assistant new file mode 100644 index 0000000..2b7d504 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: rm_eco65_description + relative_path: urdf/rm_eco65.urdf.xacro + srdf: + relative_path: config/rm_eco65_description.srdf + package_settings: + author_name: Kaola + author_email: Kaola@qq.com + generated_timestamp: 1699967197 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/CMakeLists.txt new file mode 100644 index 0000000..e1fab68 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_eco65_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/initial_positions.yaml new file mode 100644 index 0000000..92a4764 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for rm_eco65_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/joint_limits.yaml new file mode 100644 index 0000000..476ad64 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.1400000000000001 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.9199999999999999 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/kinematics.yaml new file mode 100644 index 0000000..ae2a6d5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit.rviz new file mode 100644 index 0000000..f65a4c6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: baselink + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: baselink + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..603c9db --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/moveit_controllers.yaml @@ -0,0 +1,19 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..c7c7205 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_6fb_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_6fb_description.urdf.xacro new file mode 100644 index 0000000..8341971 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_6fb_description.urdf.xacro @@ -0,0 +1,19 @@ + + + + + + + + + link6_type:=$(arg link6_type) + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.ros2_control.xacro new file mode 100644 index 0000000..4457bfa --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.ros2_control.xacro @@ -0,0 +1,56 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.srdf new file mode 100644 index 0000000..1eb3b75 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.srdf @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.urdf.xacro new file mode 100644 index 0000000..ad02779 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/rm_eco65_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..eed1e07 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo.launch.py new file mode 100644 index 0000000..df98f0f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6f.launch.py new file mode 100644 index 0000000..9989aad --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6f.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6fb.launch.py new file mode 100644 index 0000000..b8f2bea --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/demo_6fb.launch.py @@ -0,0 +1,293 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from moveit_configs_utils import MoveItConfigsBuilder +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) + +from srdfdom.srdf import SRDF +from launch_ros.parameter_descriptions import ParameterValue + +def generate_launch_description(): + """ + Launches a self contained demo + + Includes + * static_virtual_joint_tfs + * robot_state_publisher + * move_group + * moveit_rviz + * warehouse_db (optional) + * ros2_control_node + controller spawners + """ + + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + ld.add_action( + DeclareBooleanLaunchArg( + "db", + default_value=False, + description="By default, we do not start a database (it can be large)", + ) + ) + ld.add_action( + DeclareBooleanLaunchArg( + "debug", + default_value=False, + description="By default, we are not in debug mode", + ) + ) + ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=True)) + + # If there are virtual joints, broadcast static tf by including virtual_joints launch + generate_static_virtual_joint_tfs_launch(ld,moveit_config) + # Given the published joint states, publish tf for the robot links + generate_rsp_launch(ld,moveit_config) + + generate_move_group_launch(ld, moveit_config) + + generate_moveit_rviz_launch(ld, moveit_config) + + # generate_warehouse_db_launch(ld, moveit_config) + # Warehouse mongodb server + db_config = LaunchConfiguration("db") + ld.add_action( + Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + parameters=[ + {"warehouse_port": 33829}, + {"warehouse_host": "localhost"}, + {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, + ], + output="screen", + condition=IfCondition(db_config), + ) + ) + + # Fake joint driver + ld.add_action( + Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[ + moveit_config.robot_description, + str(moveit_config.package_path / "config/ros2_controllers.yaml"), + ], + ) + ) + + generate_spawn_controllers_launch(ld, moveit_config) + + + return ld + + +def generate_static_virtual_joint_tfs_launch(ld, moveit_config): + + name_counter = 0 + + for key, xml_contents in moveit_config.robot_description_semantic.items(): + srdf = SRDF.from_xml_string(xml_contents) + for vj in srdf.virtual_joints: + ld.add_action( + Node( + package="tf2_ros", + executable="static_transform_publisher", + name=f"static_transform_publisher{name_counter}", + output="log", + arguments=[ + "--frame-id", + vj.parent_frame, + "--child-frame-id", + vj.child_link, + ], + ) + ) + name_counter += 1 + return ld + +def generate_rsp_launch(ld, moveit_config): + """Launch file for robot state publisher (rsp)""" + + ld.add_action(DeclareLaunchArgument("publish_frequency", default_value="15.0")) + + # Given the published joint states, publish tf for the robot links and the robot description + rsp_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + respawn=True, + output="screen", + parameters=[ + moveit_config.robot_description, + { + "publish_frequency": LaunchConfiguration("publish_frequency"), + }, + ], + ) + ld.add_action(rsp_node) + + return ld + +def generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + +def generate_warehouse_db_launch(ld, moveit_config): + """Launch file for warehouse database""" + ld.add_action( + DeclareLaunchArgument( + "moveit_warehouse_database_path", + default_value=str( + moveit_config.package_path / "default_warehouse_mongo_db" + ), + ) + ) + ld.add_action(DeclareBooleanLaunchArg("reset", default_value=False)) + + # The default DB port for moveit (not default MongoDB port to avoid potential conflicts) + ld.add_action(DeclareLaunchArgument("moveit_warehouse_port", default_value="33829")) + + # The default DB host for moveit + ld.add_action( + DeclareLaunchArgument("moveit_warehouse_host", default_value="localhost") + ) + + # Load warehouse parameters + db_parameters = [ + { + "overwrite": False, + "database_path": LaunchConfiguration("moveit_warehouse_database_path"), + "warehouse_port": LaunchConfiguration("moveit_warehouse_port"), + "warehouse_host": LaunchConfiguration("moveit_warehouse_host"), + "warehouse_exec": "mongod", + "warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection", + }, + ] + # Run the DB server + db_node = Node( + package="warehouse_ros_mongo", + executable="mongo_wrapper_ros.py", + # TODO(dlu): Figure out if this needs to be run in a specific directory + # (ROS 1 version set cwd="ROS_HOME") + parameters=db_parameters, + ) + ld.add_action(db_node) + + # If we want to reset the database, run this node + reset_node = Node( + package="moveit_ros_warehouse", + executable="moveit_init_demo_warehouse", + output="screen", + condition=IfCondition(LaunchConfiguration("reset")), + ) + ld.add_action(reset_node) + + return ld + +def generate_spawn_controllers_launch(ld, moveit_config): + controller_names = moveit_config.trajectory_execution.get( + "moveit_simple_controller_manager", {} + ).get("controller_names", []) + for controller in controller_names + ["joint_state_broadcaster"]: + ld.add_action( + Node( + package="controller_manager", + executable="spawner", + arguments=[controller], + output="screen", + ) + ) + return ld \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..9b1c6ab --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6f.launch.py new file mode 100644 index 0000000..4c5ff55 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6f.launch.py @@ -0,0 +1,119 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..f528867 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/gazebo_moveit_demo_6fb.launch.py @@ -0,0 +1,119 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/move_group.launch.py new file mode 100644 index 0000000..b822ffb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..6acd22a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..e0faaf4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,123 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from launch_ros.substitutions import FindPackageShare + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6f.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6f.launch.py new file mode 100644 index 0000000..29c46a2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6f.launch.py @@ -0,0 +1,127 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from launch_ros.substitutions import FindPackageShare + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6f"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6fb.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6fb.launch.py new file mode 100644 index 0000000..d077d21 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/real_moveit_demo_6fb.launch.py @@ -0,0 +1,127 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue +from launch_ros.substitutions import FindPackageShare + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config") + .robot_description(file_path="config/rm_eco65_6fb_description.urdf.xacro", mappings={"link6_type": "Link6_6fb"}) + .to_moveit_configs() + ) + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/rsp.launch.py new file mode 100644 index 0000000..d4b6468 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..7fff2a6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..71af7cd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..0670146 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..67b8a81 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_eco65_description", package_name="rm_eco65_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/package.xml new file mode 100644 index 0000000..e56e6a2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_eco65_config/package.xml @@ -0,0 +1,52 @@ + + + + rm_eco65_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_eco65_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/.setup_assistant b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/.setup_assistant new file mode 100644 index 0000000..d045501 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/.setup_assistant @@ -0,0 +1,10 @@ +moveit_setup_assistant_config: + urdf: + package: rm_description + relative_path: urdf/rm_gen72.urdf + srdf: + relative_path: config/rm_gen72_description.srdf + package_settings: + author_name: Kaola + author_email: 2209099554@qq.com + generated_timestamp: 1719981638 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/CMakeLists.txt new file mode 100644 index 0000000..fdefd7d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(rm_gen72_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/initial_positions.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/initial_positions.yaml new file mode 100644 index 0000000..61bca48 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/initial_positions.yaml @@ -0,0 +1,10 @@ +# Default initial positions for rm_75_description's ros2_control fake system + +initial_positions: + joint1: 0 + joint2: 0 + joint3: 0 + joint4: 0 + joint5: 0 + joint6: 0 + joint7: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/joint_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/joint_limits.yaml new file mode 100644 index 0000000..9435c6b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/joint_limits.yaml @@ -0,0 +1,45 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 + joint7: + has_velocity_limits: true + max_velocity: 3.141 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/kinematics.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/kinematics.yaml new file mode 100644 index 0000000..bbd16e6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +rm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit.rviz b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit.rviz new file mode 100644 index 0000000..99bb740 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..f0c9381 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/moveit_controllers.yaml @@ -0,0 +1,20 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - rm_group_controller + + rm_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + - joint7 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/pilz_cartesian_limits.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..b2997ca --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_II_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_II_description.urdf.xacro new file mode 100644 index 0000000..a5effa3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_II_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.ros2_control.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.ros2_control.xacro new file mode 100644 index 0000000..5f0434d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.ros2_control.xacro @@ -0,0 +1,63 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint1']} + + + + + + + ${initial_positions['joint2']} + + + + + + + ${initial_positions['joint3']} + + + + + + + ${initial_positions['joint4']} + + + + + + + ${initial_positions['joint5']} + + + + + + + ${initial_positions['joint6']} + + + + + + + ${initial_positions['joint7']} + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.srdf b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.srdf new file mode 100644 index 0000000..041784d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.srdf @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.urdf.xacro b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.urdf.xacro new file mode 100644 index 0000000..f8691bb --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/rm_gen72_description.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/ros2_controllers.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..7e8b6e5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/config/ros2_controllers.yaml @@ -0,0 +1,27 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + rm_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +rm_group_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + - joint7 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/demo.launch.py new file mode 100644 index 0000000..bd21a4c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo.launch.py new file mode 100644 index 0000000..741cd02 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo.launch.py @@ -0,0 +1,114 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo_II.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo_II.launch.py new file mode 100644 index 0000000..aa75677 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/gazebo_moveit_demo_II.launch.py @@ -0,0 +1,119 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config") + .robot_description(file_path="config/rm_gen72_II_description.urdf.xacro") + .to_moveit_configs() + ) + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": should_publish, + "publish_geometry_updates": should_publish, + "publish_state_updates": should_publish, + "publish_transforms_updates": should_publish, + "monitor_dynamics": False, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + ] + move_group_params.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + rviz_parameters.append({"use_sim_time": True}) + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/move_group.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/move_group.launch.py new file mode 100644 index 0000000..ed6357c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/moveit_rviz.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..3f3913d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo.launch.py new file mode 100644 index 0000000..fb621b3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo.launch.py @@ -0,0 +1,122 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + "monitor_dynamics": False, + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo_II.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo_II.launch.py new file mode 100644 index 0000000..879d213 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/real_moveit_demo_II.launch.py @@ -0,0 +1,126 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + +from launch import LaunchDescription +from launch.actions import ( + DeclareLaunchArgument, + IncludeLaunchDescription, +) +from moveit_configs_utils.launch_utils import ( + add_debuggable_node, + DeclareBooleanLaunchArg, +) +from launch.substitutions import LaunchConfiguration +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + # moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + moveit_config = ( + MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config") + .robot_description(file_path="config/rm_gen72_II_description.urdf.xacro") + .to_moveit_configs() + ) + ld = LaunchDescription() + + # 启动move_group + my_generate_move_group_launch(ld, moveit_config) + # 启动rviz + my_generate_moveit_rviz_launch(ld, moveit_config) + + # generate_rsp_launch(ld, moveit_config) + + return ld + + +def my_generate_move_group_launch(ld, moveit_config): + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) + ) + ld.add_action( + DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) + ) + # load non-default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) + # inhibit these default MoveGroup capabilities (space separated) + ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) + + # do not copy dynamics information from /joint_states to internal robot monitoring + # default to false, because almost nothing in move_group relies on this information + ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) + + should_publish = LaunchConfiguration("publish_monitored_planning_scene") + + move_group_configuration = { + "publish_robot_description_semantic": True, + "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), + # Note: Wrapping the following values is necessary so that the parameter value can be the empty string + "capabilities": ParameterValue( + LaunchConfiguration("capabilities"), value_type=str + ), + "disable_capabilities": ParameterValue( + LaunchConfiguration("disable_capabilities"), value_type=str + ), + # Publish the planning scene of the physical robot so that rviz plugin can know actual robot + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + "monitor_dynamics": False, + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.15, + } + + move_group_params = [ + moveit_config.to_dict(), + move_group_configuration, + trajectory_execution, + ] + + add_debuggable_node( + ld, + package="moveit_ros_move_group", + executable="move_group", + commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), + output="screen", + parameters=move_group_params, + extra_debug_args=["--debug"], + # Set the display variable, in case OpenGL code is used internally + additional_env={"DISPLAY": ":0"}, + ) + return ld + +def my_generate_moveit_rviz_launch(ld, moveit_config): + """Launch file for rviz""" + + ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) + ld.add_action( + DeclareLaunchArgument( + "rviz_config", + default_value=str(moveit_config.package_path / "config/moveit.rviz"), + ) + ) + + rviz_parameters = [ + moveit_config.planning_pipelines, + moveit_config.robot_description_kinematics, + ] + + add_debuggable_node( + ld, + package="rviz2", + executable="rviz2", + output="log", + respawn=False, + arguments=["-d", LaunchConfiguration("rviz_config")], + parameters=rviz_parameters, + ) + + return ld + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/rsp.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/rsp.launch.py new file mode 100644 index 0000000..3b414d9 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/setup_assistant.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..0a046df --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/spawn_controllers.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..e56ede4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/static_virtual_joint_tfs.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..057574b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/warehouse_db.launch.py b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..d4de4ff --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("rm_gen72_description", package_name="rm_gen72_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/package.xml new file mode 100644 index 0000000..cc9e25a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_moveit2_config/rm_gen72_config/package.xml @@ -0,0 +1,51 @@ + + + + rm_gen72_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the rm_gen72_description with the MoveIt Motion Planning Framework + + Kaola + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Kaola + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + rm_description + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + + + + ament_cmake + + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/CMakeLists.txt b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/CMakeLists.txt new file mode 100755 index 0000000..49be126 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/CMakeLists.txt @@ -0,0 +1,116 @@ +cmake_minimum_required(VERSION 3.8) +project(rm_ros_interfaces) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(builtin_interfaces REQUIRED) + +# find dependencies + +set(msg_files + msg/Movej.msg + # msg/Movej75.msg + msg/Movejp.msg + msg/Movel.msg + msg/Movec.msg + msg/Jointteach.msg + msg/Posteach.msg + msg/Ortteach.msg + msg/Setrealtimepush.msg + msg/Armsoftversion.msg + msg/Softwarebuildinfo.msg + msg/Sixforce.msg + msg/Jointerrorcode.msg + msg/Forcepositionmovejoint.msg + # msg/Forcepositionmovejoint75.msg + msg/Forcepositionmovepose.msg + msg/Setforceposition.msg + msg/Getallframe.msg + msg/Jointpos.msg + # msg/Jointpos75.msg + msg/Cartepos.msg + msg/Jointerrclear.msg + msg/Gripperpick.msg + msg/Gripperset.msg + msg/Handangle.msg + msg/Handforce.msg + msg/Handposture.msg + msg/Handseq.msg + msg/Handspeed.msg + msg/Handstatus.msg + msg/Armoriginalstate.msg + msg/Armstate.msg + msg/Liftspeed.msg + msg/Liftheight.msg + msg/Liftstate.msg + msg/Armcurrentstatus.msg + msg/Jointcurrent.msg + msg/Jointenflag.msg + msg/Jointposeeuler.msg + msg/Jointspeed.msg + msg/Jointtemperature.msg + msg/Jointvoltage.msg + msg/Carteposcustom.msg + msg/Jointposcustom.msg + msg/Rmplusbase.msg + msg/Rmplusstate.msg + msg/Rmerr.msg + # 四代控制器适配新增 + # msg/Armsoftversionv3.msg + # msg/Armsoftversionv4.msg + msg/RobotInfo.msg + # msg/Rmversion.msg + msg/Flowchartrunstate.msg + msg/Trajectoryinfo.msg + msg/Trajectorylist.msg + msg/Modbustcpmasterinfo.msg + msg/Modbustcpmasterupdata.msg + msg/Modbustcpmasterlist.msg + msg/Modbustcpreadparams.msg + msg/Modbustcpwriteparams.msg + msg/Modbusrtureadparams.msg + msg/Modbusrtuwriteparams.msg + msg/Programrunstate.msg + msg/Toolsoftwareversionv4.msg + msg/Moveloffset.msg + msg/Jointversion.msg + msg/Stop.msg + msg/Mastername.msg + msg/Getmodbustcpmasterlist.msg + msg/RS485params.msg + msg/Modbusreaddata.msg + msg/Gettrajectorylist.msg + msg/Sendproject.msg +) + +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + DEPENDENCIES + std_msgs + geometry_msgs + builtin_interfaces +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README.md new file mode 100755 index 0000000..6bb0502 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README.md @@ -0,0 +1,761 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_ros_interfaces/README_CN.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_ros_interfaces/README.md) + +
+ +
+ +# RealMan Robot rm_ros_interface User Manual V1.2 + + + + + +RealMan Intelligent Technology (Beijing) Co., Ltd. + +Revision History- + +| No. | Date| Comment | +| -----| -----| -----| +|V1.0 | 2-18-2024 | Draft | +|V1.1 | 7-8-2024 | Amend(Add teaching message) | +|V1.2 | 12-25-2024 | Amend(Add UDP report message) | +|V1.3 | 04-07-2025 | Amend(API2 Adaptation) | + + +
+ +## 目录 +* 1[rm_ros_interface Package Description](#rm_ros_interface_Package_Description) +* 2[rm_ros_interface Package Use](#rm_ros_interface_Package_Use) +* 3[rm_ros_interface Package Architecture Description](#rm_ros_interface_Package_Architecture_Description) +* 3.1[Overview of Package Files](#Overview_of_Package_Files) +* 4[rm_ros_interface message description](#rm_ros_interface_message_description) +* 4.1[Joint error code-Jointerrorcode_msg](#Joint_error_code-Jointerrorcode_msg) +* 4.2[Clearing the joint's error code-Jointerrclear_msg](#Clearing_the_joint's_error_code-Jointerrclear_msg) +* 4.3[All coordinate system names-Getallframe_msg](#All_coordinate_system_names-Getallframe_msg) +* 4.4[Joine motion-Movej_msg](#Joine_motion-Movej_msg) +* 4.5[Linear motion-Movel_msg](#Linear_motion-Movel_msg) +* 4.6[Circular motion-Movec_msg](#Circular_motion-Movec_msg) +* 4.7[Joint space planning to target pose-Movejp_msg](#Joint_space_planning_to_target_pose-Movejp_msg) +* 4.8[Joint teaching-Jointteach_msg-Jointteach_msg](#Joint_teaching-Jointteach_msg) +* 4.9[Position teaching-Posteach_msg](#Position_teaching-Posteach_msg) +* 4.10[Attitude teaching-Ortteach_msg](#Attitude_teaching-Ortteach_msg) +* 4.11[Joint transmission-Jointpos_msg](#Joint_transmission-Jointpos_msg) +* 4.12[Pose transmission-Cartepos_msg](#Pose_transmission-Cartepos_msg) +* 4.13[Current robotic arm state Angle and Euler angle-Armoriginalstate_msg](#Current_robotic_arm_state_Angle_and_Euler_angle-Armoriginalstate_msg) +* 4.14[Current arm state radians and quaternion-Armstate_msg](#Current_arm_state_radians_and_quaternion-Armstate_msg) +* 4.15[Gripper's pick-Gripperpick_msg](#Gripper's_pick-Gripperpick_msg) +* 4.16[Gripper's pick gripper's pick-on-Gripperpick_msg](#Gripper's_pick_gripper's_pick-on-Gripperpick_msg) +* 4.17[Gripper reaching the given position-Gripperset_msg](#Gripper_reaching_the_given_position-Gripperset_msg) +* 4.18[Force-position mixing control-Setforceposition_msg](#Force-position_mixing_control-Setforceposition_msg) +* 4.19[Six-axis force data-Sixforce_msg](#Six-axis_force_data-Sixforce_msg) +* 4.20[Setting the dexterous hand posture-Handposture_msg](#Setting_the_dexterous_hand_posture-Handposture_msg) +* 4.21[Setting the dexterous hand action sequence-Handseq_msg](#Seting_the_dexterous_hand_action_sequence-Handseq_msg) +* 4.22[Setting the angles of various degrees of freedom for the dexterous hand-Handangle_msg](#Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand-Handangle_msg) +* 4.23[Setting the dexterous hand action sequence-Handspeed_msg](#Setting_the_dexterous_hand_action_sequence-Handspeed_msg) +* 4.24[Setting the force threshold for the dexterous hand-Handforce_msg](#Setting_the_force_threshold_for_the_dexterous_hand-Handforce_msg) +* 4.25[Transmissive force-position mixing control compensation-angle-Forcepositionmovejoint_msg](#Transmissive_force-position_mixing_control_compensation-angle-Forcepositionmovejoint_msg) +* 4.26[Transmissive force-position mixing control compensation-pose-Forcepositionmovejoint_msg](#Transmissive_force-position_mixing_control_compensation-pose-Forcepositionmovejoint_msg) +* 4.27[Speed open loop control-lifting mechanism-Liftspeed_msg](#Speed_open_loop_control-lifting_mechanism-Liftspeed_msg) +* 4.28[Position closed-loop control-lifting mechanism-Lift height_msg](#Position_closed-loop_control-lifting_mechanism-Lift_height_msg) +* 4.29[Getting the state of the lifting mechanism-Liftstate_msg](#Getting_the_state_of_the_lifting_mechanism-Liftstate_msg) +* 4.30[Getting or setting UDP active reporting configuration-Setrealtimepush_msg](#Getting_or_setting_UDP_active_reporting_configuration-Setrealtimepush_msg) +* 4.31[UDP manipulator status report Armcurrentstatus_msg](#UDP_manipulator_status_report-Armcurrentstatus_msg) +* 4.32[UDP joint current report Jointcurrent_msg](#UDP_joint_current_report-Jointcurrent_msg) +* 4.33[UDP joint enabling status report Jointenflag_msg](#UDP_joint_enabling_status_report-Jointenflag_msg) +* 4.34[UDP manipulator Euler's angular pose is reported to Jointposeeuler_msg](#UDP_manipulator_Eulers_angular_pose_is_reported_to-Jointposeeuler_msg) +* 4.35[UDP joint speed report Jointspeed_msg](#UDP_joint_speed_report_Jointspeed_msg) +* 4.36[UDP joint temperature report Jointtemperature_msg](#UDP_joint_temperature_report_Jointtemperature_msg) +* 4.37[UDP joint voltage report Jointvoltage_msg](#UDP_joint_voltage_report_Jointvoltage_msg) +* 4.38[System error code_Rmerr_msg](#System_error_code_Rmerr_msg) +* 4.39[Basic information of the end-effector device_Rmplusbase_msg](#Basic_information_of_the_end_effector_device_Rmplusbase_msg) +* 4.40[Real time information of the end_effector device-Rmplusstate_msg](#Real_time_information_of_the_end_effector_deviceRmplusstate_msg) +* 4.41[Customize high following mode joint transmission-Jointposcustom_msg](#Customize_high_following_mode_joint_transmission_Jointposcustom_msg) +* 4.42[Customize high following mode pose transmission-Carteposcustom_msg](#Customize_high_following_mode_pose_transmission_Carteposcustom_msg) + +## rm_ros_interface_Package_Description +The main function of the rm_ros_interface package is to provide necessary message files for the robotic arm to run under the framework of ROS2. In the following text, we will provide a detailed introduction to this package through the following aspects. +* 1.Package use. +* 2.Package architecture description. +* 3.Package topic description. +Through the introduction of the three parts, it can help you- +* 1.Understand the package use. +* 2.Familiar with the file structure and function of the package. +* 3.Familiar with the topic related to the package for easy development and use. +## rm_ros_interface_Package_Use +This package does not have any executable commands, but it is used to provide the necessary message files for other packages. +## rm_ros_interface_Package_Architecture_Description +### Overview_of_Package_Files +``` +├── CMakeLists.txt # compilation rule file +├── include # dependency header file folder +│ └── rm_ros_interfaces +├── msg # current message file (see below for details) +│ ├── Armcurrentstatus.msg +│ ├── Armoriginalstate.msg +│ ├── Armstate.msg +│ ├── Cartepos.msg +│ ├── Carteposcustom.msg +│ ├── Forcepositionmovejoint.msg +│ ├── Forcepositionmovepose.msg +│ ├── Force_Position_State.msg +│ ├── Getallframe.msg +│ ├── GetArmState_Command.msg +│ ├── Gripperpick.msg +│ ├── Gripperset.msg +│ ├── Handangle.msg +│ ├── Handforce.msg +│ ├── Handposture.msg +│ ├── Handseq.msg +│ ├── Handspeed.msg +│ ├── Handstatus.msg +│ ├── Jointcurrent.msg +│ ├── Jointenflag.msg +│ ├── Jointerrclear.msg +│ ├── Jointerrorcode.msg +│ ├── Jointposeeuler.msg +│ ├── Jointpos.msg +│ ├── Jointposcustom.msg +│ ├── Jointspeed.msg +│ ├── Jointteach.msg +│ ├── Jointtemperature.msg +│ ├── Jointvoltage.msg +│ ├── Liftheight.msg +│ ├── Liftspeed.msg +│ ├── Liftstate.msg +│ ├── Movec.msg +│ ├── Movej.msg +│ ├── Movejp.msg +│ ├── Movel.msg +│ ├── Ortteach.msg +│ ├── Posteach.msg +│ ├── Setforceposition.msg +│ ├── Setrealtimepush.msg +│ ├── Sixforce.msg +│ └── Stop.msg +├── package.xml # dependency declaration file +└── src +``` +## rm_ros_interface_message_description +### Joint_error_code-Jointerrorcode_msg +``` +uint16[] joint_error +uint8 dof +``` +__msg member__ +__uint16[] joint_error__ +Error message for each joint. +__uint8 dof__ +Degree of freedom message of the robotic arm. +### Clearing_the_joint's_error_code-Jointerrclear_msg +``` +uint8 joint_num +``` +__msg member__ +__joint_num__ +the corresponding joint number, from the base to the robotic arm gripper, the number is 1-6 or 1-7. +### All_coordinate_system_names-Getallframe_msg +``` +string[10] frame_name +``` +__msg member__ +__frame_name__ +The array of work coordinate system names returned +### Joine_motion-Movej_msg +``` +float32[] joint +uint8 speed +bool block +uint8 trajectory_connect +uint8 dof +``` +__msg member__ +__joint__ +Joint angle, float type, unit-radians. +__speed__ +Speed percentage ratio coefficient, 0-100. +__trajectory_connect__ +Is the trajectory plan now. 1.wait 0.plan now. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__dof__ +Degree of freedom message of the robotic arm. +### Linear_motion-Movel_msg +``` +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect +bool block +``` +__msg member__ +__pose__ +Robotic arm pose-geometry_msgs/Pose type, x, y, z coordinates (float type, unit-m) + quaternion (float type). +__speed__ +Speed percentage ratio coefficient, 0-100. +__trajectory_connect__ +Is the trajectory plan now. 1.wait 0.plan now. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Circular_motion-Movec_msg +``` +geometry_msgs/Pose pose_mid +geometry_msgs/Pose pose_end +uint8 speed +uint8 trajectory_connect +bool block +uint8 loop +``` +__msg member__ +__pose_mid__ +Middle pose: geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion. +__pose_end__ +Target pose: geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion. +__speed__ +Speed percentage ratio coefficient, 0-100. +__trajectory_connect__ +Is the trajectory plan now. 1.wait 0.plan now. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__loop__ +Number of cycles +### Joint_space_planning_to_target_pose-Movejp_msg +``` +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect +bool block +``` +__msg member__ +__pose__ +Target pose: geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion. +__speed__ +Speed percentage ratio coefficient, 0-100. +__trajectory_connect__ +Is the trajectory plan now. 1.wait 0.plan now. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Joint_teaching-Jointteach_msg +``` +uint8 num +uint8 direction +uint8 speed +``` +__msg member__ +__num__ +joint num,1~7. +__direction__ +teach direction,0-negative direction,1-positive direction. +__speed__ +speed:speed percentage ratio coefficient, 0-100. +### Position_teaching-Posteach_msg +``` +uint8 type +uint8 direction +uint8 speed +``` +__msg member__ +__type__ +Teaching demonstration type: input0:X-axis direction、1:Y-axis direction、2:Z-axis direction. +__direction__ +teach direction,0-negative direction,1-positive direction. +__speed__ +speed:speed percentage ratio coefficient, 0-100. +### Attitude_teaching-Ortteach_msg +``` +uint8 type +uint8 direction +uint8 speed +``` +__msg member__ +__type__ +Teaching demonstration type: input0:RX-axis direction、1:RY-axis direction、2:RZ-axis direction +__direction__ +teach direction,0-negative direction,1-positive direction. +__speed__ +speed:speed percentage ratio coefficient, 0-100. +### Joint_transmission-Jointpos_msg +``` +float32[] joint +bool follow +float32 expand +uint8 dof +``` +__msg member__ +__joint__ +Joint angle, float type, unit: radians. +__follow__ +Follow state, bool type, true: high follow, false: low follow, default high follow if not set. +__expand__ +Expand joint, float type, unit: radians. +__dof__ +Degree of freedom message of the robotic arm. +### Pose_transmission-Cartepos_msg +``` +geometry_msgs/Pose pose +bool follow +``` +__msg member__ +__pose__ +Robotic arm poses geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion. +__follow__ +Follow state, bool type, true: high follow, false: low follow, default high follow if not set. +### Current_robotic_arm_state_Angle_and_Euler_angle-Armoriginalstate_msg +``` +float32[] joint +float32[6] pose +uint16 arm_err +uint16 sys_err +uint8 dof +``` +__msg member__ +__joint__ +Joint angle, float type, unit: °. +__pose__ +Current pose of the robotic arm, float type, x, y, z coordinates, unit: m, x, y, z Euler angle, unit: degree. +__arm_err__ +Robotic arm running error code, unsigned int type. +__arm_err__ +Controller error code, unsigned int type. +__dof__ +Degree of freedom message of the robotic arm. +### Current_arm_state_radians_and_quaternion-Armstate_msg +``` +float32[] joint +geometry_msgs/Pose pose +uint16 arm_err +uint16 sys_err +uint8 dof +``` +__msg member__ +__joint__ +Joint angle, float type, unit: radians. +__pose__ +Current pose of the robotic arm, float type, x, y, z coordinates, unit: m, x, y, z, w quaternion. +__arm_err__ +Robotic arm running error code, unsigned int type. +__arm_err__ +Controller error code, unsigned int type. +__dof__ +Degree of freedom message of the robotic arm. +### Gripper_pick-Gripperpick_msg +``` +uint16 speed +uint16 force +bool block +uint16 timeout +``` +__msg member__ +__speed__ +Gripper pick speed, unsigned int type, range: 1-1000. +__force__ +Gripper pick torque threshold, unsigned int type, range: 50-1000. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__timeout__ +Set the timeout for the return, and the blocking mode will take effect (in seconds). +### Gripper_pick_gripper_pick-on-Gripperpick_msg +``` +uint16 speed +uint16 force +bool block +uint16 timeout +``` +__msg member__ +__speed__ +Gripper pick speed, unsigned int type, range: 1-1000. +__force__ +Gripper picks torque threshold, unsigned int type, range: 50-1000. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__timeout__ +Set the timeout for the return, and the blocking mode will take effect (in seconds). +### Gripper_reaching_the_given_position-Gripperset_msg +``` +uint16 position +bool block +uint16 timeout +``` +__msg member__ +__position__ +Gripper target position, unsigned int type, range: 1-1000, representing the degree of opening of the gripper: 0-70 mm. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__timeout__ +Set the timeout for the return, and the blocking mode will take effect (in seconds). +### Force-position_mixing_control-Setforceposition_msg +``` +uint8 sensor +uint8 mode +uint8 direction +int16 n +``` +__msg member__ +__sensor__ +Sensor; 0 - One-axis force; 1 - Six-axis force. +__mode__ +Mode: 0 - Base coordinate system force control; 1 - Tool coordinate system force control. +__Direction__ +Force control direction; 0 - Along the X-axis; 1 - Along the Y-axis; 2 - Along the Z-axis; 3 - Along the RX posture direction; 4 - Along the RY posture direction; 5 - Along the RZ posture direction. +__n__ +Force value, unit: 0.1 N. +### Six-axis_force_data-Sixforce_msg +``` +float32 force_fx +float32 force_fy +float32 force_fz +float32 force_mx +float32 force_my +float32 force_mz +``` +__msg member__ +__force_fx__ +the force along the x-axis direction. +__force_fy__ +the force along the y-axis direction. +__force_fz__ +the force along the z-axis direction. +__force_mx__ +the force when rotating along the x-axis direction. +__force_my__ +the force when rotating along the y-axis direction. +__force_mz__ +the force when rotating along the z-axis direction. +### Setting_the_dexterous_hand_posture-Handposture_msg +``` +uint16 posture_num +bool block +uint16 timeout +``` +__msg member__ +__posture_num__ +The serial number of the posture pre-saved in the dexterous hand, ranges from 1 to 40. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__timeout__ +The timeout setting for blocking mode, unit: seconds. +### Setting_the_dexterous_hand_action_sequence-Handseq_msg +``` +uint16 seq_num +bool block +unint16 timeout +``` +__msg member__ +__seq_num__ +The serial number of the sequence pre-saved in the dexterous hand, ranging from 1 to 40. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +__timeout__ +The timeout setting for blocking mode, unit: seconds. +### Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand-Handangle_msg +``` +int16[6] hand_angle +bool block +``` +__msg member__ +__hand_angle__ +Hand angle array, range: 0-1000. And -1 represents that no operation is performed on this degree of freedom and the current state remains. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Setting_the_dexterous_hand_action_sequence-Handspeed_msg +``` +uint16 hand_speed +``` +__msg member__ +__hand_speed__ +Hand speed, range: 1-1000. +### Setting_the_force_threshold_for_the_dexterous_hand-Handforce_msg +``` +uint16 hand_force +``` +__msg member__ +__hand_force__ +Hand force, range: 1-1000. +### Transmissive_force-position_mixing_control_compensation-angle-Forcepositionmovejoint_msg +``` +float32[] joint +uint8 sensor +uint8 mode +int16 dir +float32 force +bool follow +uint8 dof +``` +__msg member__ +__joint__ +Angle force-position mixing transmission, unit: radians. +__sensor__ +Type of sensor used, 0 - One-axis force, 1 - Six-axis force. +__mode__ +Mode, 0 - Along the work coordinate system, 1 - Along the tool end coordinate system. +__dir__ +Force control direction, 0 to 5 represent X/Y/Z/Rx/Ry/Rz respectively, and the default direction for one-axis force type is the Z direction. +__force__ +Force value, accuracy: 0.1 N or 0.1 Nm. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +dof +Degree of freedom message of the robotic arm. +### Transmissive_force-position_mixing_control_compensation-pose-Forcepositionmovejoint_msg +``` +geometry_msgs/Pose pose +uint8 sensor +uint8 mode +int16 dir +float32 force +bool follow +``` +__msg member__ +__pose__ +Robotic arm pose message, x, y, z position message + quaternion posture message. +__sensor__ +Type of sensor used, 0 - One-axis force, 1 - Six-axis force. +__mode__ +Mode, 0 - Along the work coordinate system, 1 - Along the tool end coordinate system. +__dir__ +Force control direction, 0 to 5 represent X/Y/Z/Rx/Ry/Rz respectively, and the default direction for one-axis force type is the Z direction. +__force__ +Force value, accuracy: 0.1 N or 0.1 Nm. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Speed_open_loop_control-lifting_mechanism-Liftspeed_msg +``` +int16 speed +bool block +``` +__msg member__ +__speed__ +Speed percentage, -100-100. Speed < 0: the lifting mechanism moves downward; Speed > 0: the lifting mechanism moves upward; Speed = 0: the lifting mechanism stops. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Position_closed-loop_control-lifting_mechanism-Lift_height_msg +``` +uint16 height +uint16 speed +bool block +``` +__msg member__ +__height__ +Target height, unit: mm, accuracy: 0-2600. +__speed__ +Speed percentage, 1-100. +__block__ +whether it is a blocking mode, bool type, true-blocking, false-non-blocking. +### Getting_the_state_of_the_lifting_mechanism-Liftstate_msg +``` +int16 height +int16 current +uint16 err_flag +``` +__msg member__ +__height__ +Current lifting mechanism height, unit: mm, accuracy: 1mm, range: 0-2300. +__current__ +Lifting drive error code, error code type refers to joint error code. +### Getting_or_setting_UDP_active_reporting_configuration-Setrealtimepush_msg +``` +uint16 cycle +uint16 port +uint16 force_coordinate +string ip +bool aloha_state_enable +bool arm_current_status_enable +bool expand_state_enable +bool hand_enable +bool joint_speed_enable +bool lift_state_enable +bool plus_base_enable +bool plus_state_enable +``` +__msg member__ +__cycle__ +Set the broadcast cycle, which is a multiple of 5ms. +__port__ +Set the port number for broadcasting. +__force_coordinate__ +Coordinate system for external force data of the system, where 0 is the sensor coordinate system, 1 is the current work coordinate system, and 2 is the current tool coordinate system. +__ip__ +Customized reporting target IP address. +__aloha_state_enable__ +aloha master arm state enable. +__arm_current_status_enable__ +arm_current_status enable. +__expand_state_enable__ +Expansion joint-related data enable. +__hand_enable__ +Dexterous hand state enable. +__joint_speed_enable__ +Current joint speed, with an accuracy of 0.02 rpm. +__lift_state_enable__ +Lifting joint data enable. +__plus_base_enable__ +Basic information of the end-effector device enable. +__plus_state_enable__ +Real-time information of the end-effector device enable. + +### UDP_manipulator_status_report-Armcurrentstatus_msg +``` +uint16 arm_current_status +``` +__msg member__ +__arm_current_status__ +Mechanical arm status, +0-RM_IDLE_E // Enabled but idle state +1-RM_MOVE_L_E // move L state in motion +2-RM_MOVE_J_E // move J in motion +3-RM_MOVE_C_E // move C state in motion +4-RM_MOVE_S_E // move S state in motion +5-RM_MOVE_THROUGH_JOINT_E // Angle transparent state +6-RM_MOVE_THROUGH_POSE_E // Pose transparent state +7-RM _ move _ through _ force _ pose _ e//Force control transparent transmission state +8-RM_MOVE_THROUGH_CURRENT_E // Current loop transparent state +9-RM_STOP_E // Emergency stop status +10-RM_SLOW_STOP_E // slow stop status +11-RM_PAUSE_E // Pause status +12-RM_CURRENT_DRAG_E // Current loop drag status +13-RM_SENSOR_DRAG_E // Six-axis force drag state +14-RM_TECH_DEMONSTRATION_E // Teaching Status +### UDP_joint_current_report-Jointcurrent_msg +``` +float32[] joint_current +``` +__msg member__ +__joint_current__ +Current joint current with an accuracy of 0.001mA. + ### UDP_joint_enabling_status_report-Jointenflag_msg +``` +bool[] joint_en_flag +``` +__msg member__ +__joint_en_flag__ +Current joint enabling state, 1 is up enabling and 0 is down enabling. +### UDP_manipulator_Eulers_angular_pose_is_reported_to-Jointposeeuler_msg +``` +float32[3] euler +float32[3] position +``` +__msg member__ +__euler__ +Euler angle of current waypoint attitude, with an accuracy of 0.001rad. +__position__ +The current waypoint position has an accuracy of 0.000001M. +### UDP_joint_speed_report_Jointspeed_msg +``` +float32[] joint_speed +``` +__msg member__ +__joint_speed__ +Current joint speed, accuracy 0.02RPM. +### UDP_joint_temperature_report_Jointtemperature_msg +``` +float32[] joint_temperature +``` +__msg member__ +__joint_temperature__ +Current joint temperature, with an accuracy of 0.001℃. +### UDP_joint_voltage_report_Jointvoltage_msg +``` +float32[] joint_voltage +``` +__msg member__ +__joint_voltage__ +Current joint voltage, with an accuracy of 0.001V V. + +### System_error_code_Rmerr_msg +``` +uint8 err_len +int32[] err +``` +__msg成员__ +__err_len__ +uint8。 +__err__ +int32。 + +### Basic_information_of_the_end_effector_device_Rmplusbase_msg +``` +string manu # Device manufacturer; +int8 type # Device type, 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper; +string hv # Hardware version; +string sv # Software version; +string bv # Bootloader version; +int32 id # Device ID; +int8 dof # Degrees of freedom; +int8 check # Self-check switch; +int8 bee # Beeper switch; +bool force # Force control support; +bool touch # Tactile support; +int8 touch_num # Number of tactile sensors; +int8 touch_sw # Tactile switch; +int8 hand # Hand orientation, 1 - Left hand, 2 - Right hand; +int32[12] pos_up # Position upper limit +int32[12] pos_low # Position lower limit +int32[12] angle_up # Angle upper limit 0.01° +int32[12] angle_low # Angle lower limit 0.01° +int32[12] speed_up # Speed upper limit +int32[12] speed_low # Speed lower limit +int32[12] force_up # Force upper limit 0.001N +int32[12] force_low # Force lower limit 0.001N +``` +### Real_time_information_of_the_end_effector_deviceRmplusstate_msg +``` +int32 sys_state #System status +int32[12] dof_state #Current status of each degree of freedom (DoF) +int32[12] dof_err #Error information of each DoF +int32[12] pos #Current position of each DoF +int32[12] speed #Current Speed of Each Degree of each DoF +int32[12] angle #Current Angle of Each Degree of each DoF +int32[12] current #Current Current of Each Degree of Freedom +int32[18] normal_force #Normal Force of Tactile Three-Dimensional Force of Each Degree of Freedom +int32[18] tangential_force #Tangential Force of Tactile Three-Dimensional Force of Each Degree of Freedom +int32[18] tangential_force_dir #Direction of Tangential Force of Tactile Three-Dimensional Force of Each Degree of Freedom +uint32[12] tsa #Tactile Self-Approach of Each Degree of Freedom +uint32[12] tma #Tactile Mutual Approach of Each Degree of Freedom +int32[18] touch_data #Raw Data of Tactile Sensors +int32[12] force #Torque of Each Degree of Freedom +``` + + +### Customize_high_following_mode_joint_transmission_Jointposcustom_msg +``` +float32[] joint +bool follow +float32 expand +uint8 dof +uint8 trajectory_mode +uint8 radio +``` +__msg member__ +__joint__ +Joint angle, float type, unit: radians. +__follow__ +Follow state, bool type, true: high follow, false: low follow, default high follow if not set. +__expand__ +Expand joint, float type, unit: radians. +__dof__ +Degree of freedom message of the robotic arm. +__trajectory_mode__ +When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode. +__radio__ +Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect. + +### Customize_high_following_mode_pose_transmission_Carteposcustom_msg +``` +geometry_msgs/Pose pose +bool follow +uint8 trajectory_mode +uint8 radio +``` +__msg member__ +__pose__ +Robotic arm poses geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion. +__follow__ +Follow state, bool type, true: high follow, false: low follow, default high follow if not set. +__trajectory_mode__ +When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode. +__radio__ +Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect. + +It is mainly for the application of API to achieve some of the robotic arm functions; for a more complete introduction and use, please see the special document "[RealMan Robotic Arm ROS2 Topic Detailed Description](https://github.com/kaola-zero/ros2_rm_robot/blob/main/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md)". \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README_CN.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README_CN.md new file mode 100755 index 0000000..e064b44 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/README_CN.md @@ -0,0 +1,763 @@ +
+ +[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_ros_interfaces/README_CN.md)| +[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_ros_interfaces/README.md) + +
+ +
+ +# 睿尔曼机器人rm_ros_interface使用说明书V1.2.1 + + + + + +睿尔曼智能科技(北京)有限公司 + +文件修订记录: + +|版本号 | 时间 | 备注 | +| :---: | :---- | :---: | +|V1.0 | 2024-2-18 | 拟制 | +|V1.1 | 2024-7-8 | 修订(添加示教消息) | +|V1.2 | 2024-12-25 | 修订(添加UDP上报消息) | +|V1.3 | 2025-04-03 | 修订(适配API2) | + +
+ +## 目录 +* 1[rm_ros_interface功能包说明](#rm_ros_interface功能包说明) +* 2[rm_ros_interface功能包使用](#rm_ros_interface功能包使用) +* 3[rm_ros_interface功能包架构说明](#rm_ros_interface功能包架构说明) +* 3.1[功能包文件总览](#功能包文件总览) +* 4[rm_ros_interface消息说明](#rm_ros_interface消息说明) +* 4.1[关节错误代码Jointerrorcode_msg](#关节错误代码Jointerrorcode_msg) +* 4.2[清除关节错误代码Jointerrclear_msg](#清除关节错误代码Jointerrclear_msg) +* 4.3[所有坐标系名称Getallframe_msg](#所有坐标系名称Getallframe_msg) +* 4.4[关节运动Movej_msg](#关节运动Movej_msg) +* 4.5[直线运动Movel_msg](#直线运动Movel_msg) +* 4.6[圆弧运动Movec_msg](#圆弧运动Movec_msg) +* 4.7[关节空间规划到目标位姿Movejp_msg](#关节空间规划到目标位姿Movejp_msg) +* 4.8[关节示教Jointteach.msg](#关节示教Jointteach_msg) +* 4.9[位置示教Posteach.msg](#位置示教Posteach_msg) +* 4.10[姿态示教Ortteach.msg](#姿态示教Ortteach_msg) +* 4.11[角度透传Jointpos_msg](#角度透传Jointpos_msg) +* 4.12[位姿透传Cartepos_msg](#位姿透传Cartepos_msg) +* 4.13[机械臂当前状态-角度和欧拉角Armoriginalstate_msg](#机械臂当前状态-角度和欧拉角Armoriginalstate_msg) +* 4.14[机械臂当前状态-弧度和四元数Armstate_msg](#机械臂当前状态-弧度和四元数Armstate_msg) +* 4.15[手爪力控夹取Gripperpick_msg](#手爪力控夹取Gripperpick_msg) +* 4.16[手爪力控夹取-持续力控夹取Gripperpick_msg](#手爪力控夹取-持续力控夹取Gripperpick_msg) +* 4.17[手爪到达指定位置Gripperset_msg](#手爪到达指定位置Gripperset_msg) +* 4.18[力位混合控制Setforceposition_msg](#力位混合控制Setforceposition_msg) +* 4.19[六维力数据Sixforce_msg](#六维力数据Sixforce_msg) +* 4.20[设置灵巧手手势Handposture_msg](#设置灵巧手手势Handposture_msg) +* 4.21[设置灵巧手动作序列Handseq_msg](#设置灵巧手动作序列Handseq_msg) +* 4.22[设置灵巧手各自由度角度Handangle_msg](#设置灵巧手各自由度角度Handangle_msg) +* 4.23[设置灵巧手速度Handspeed_msg](#设置灵巧手速度Handspeed_msg) +* 4.24[设置灵巧手力阈值Handforce_msg](#设置灵巧手力阈值Handforce_msg) +* 4.25[透传力位混合补偿-角度Forcepositionmovejoint_msg](#透传力位混合补偿-角度Forcepositionmovejoint_msg) +* 4.26[透传力位混合补偿-位姿Forcepositionmovejoint_msg](#透传力位混合补偿-位姿Forcepositionmovejoint_msg) +* 4.27[速度开环控制-升降机构Liftspeed_msg](#速度开环控制-升降机构Liftspeed_msg) +* 4.28[位置闭环控制-升降机构Liftheight_msg](#位置闭环控制-升降机构Liftheight_msg) +* 4.29[获取升降机构状态-升降机构Liftstate_msg](#获取升降机构状态-升降机构Liftstate_msg) +* 4.30[查询或设置UDP机械臂状态主动上报配置Setrealtimepush_msg](#查询或设置UDP机械臂状态主动上报配置Setrealtimepush_msg) +* 4.31[UDP机械臂状态上报Armcurrentstatus_msg](#UDP机械臂状态上报Armcurrentstatus_msg) +* 4.32[UDP关节电流上报Jointcurrent_msg](#UDP关节电流上报Jointcurrent_msg) +* 4.33[UDP关节使能状态上报Jointenflag_msg](#UUDP关节使能状态上报Jointenflag_msg) +* 4.34[UDP机械臂欧拉角位姿上报Jointposeeuler_msg](#UDP机械臂欧拉角位姿上报Jointposeeuler_msg) +* 4.35[UDP关节速度上报Jointspeed_msg](#UDP关节速度上报Jointspeed_msg) +* 4.36[UDP关节温度上报Jointtemperature_msg](#UDP关节温度上报Jointtemperature_msg) +* 4.37[UDP关节电压上报Jointvoltage_msg](#UDP关节电压上报Jointvoltage_msg) +* 4.38[机械臂UDP报错Rmerr_msg](#机械臂UDP报错Rmerr_msg) +* 4.39[末端设备基础信息Rmplusbase_msg](#末端设备基础信息Rmplusbase_msg) +* 4.40[末端设备实时信息Rmplusstate.msg](#末端设备实时信息Rmplusstate.msg) +* 4.41[自定义高跟随模式角度透传Jointposcustom_msg](#角度透传Jointposcustom_msg) +* 4.42[自定义高跟随模式位姿透传Carteposcustom_msg](#位姿透传Carteposcustom_msg) + + +## rm_ros_interface功能包说明 +rm_ros_interface功能包的主要作用为为机械臂在ROS2的框架下运行提供必要的 消息文件,在下文中将通过以下几个方面详细介绍该功能包。 +* 1.功能包使用。 +* 2.功能包架构说明。 +* 3.功能包话题说明。 +通过这三部分内容的介绍可以帮助大家: +* 1.了解该功能包的使用。 +* 2.熟悉功能包中的文件构成及作用。 +* 3.熟悉功能包相关的话题,方便开发和使用。 +## rm_ros_interface功能包使用 +该功能包并没有可执行的使用命令,其主要作用为为其他功能包提供必须的消息文件。 +## rm_ros_interface功能包架构说明 +### 功能包文件总览 +``` +当前rm_driver功能包的文件构成如下。 +├── CMakeLists.txt #编译规则文件 +├── include #依赖头文件文件夹 +│ └── rm_ros_interfaces +├── msg #当前的消息文件(详细请看下方介绍) +│ ├── Armcurrentstatus.msg +│ ├── Armoriginalstate.msg +│ ├── Armstate.msg +│ ├── Cartepos.msg +│ ├── Carteposcustom.msg +│ ├── Forcepositionmovejoint.msg +│ ├── Forcepositionmovepose.msg +│ ├── Force_Position_State.msg +│ ├── Getallframe.msg +│ ├── GetArmState_Command.msg +│ ├── Gripperpick.msg +│ ├── Gripperset.msg +│ ├── Handangle.msg +│ ├── Handforce.msg +│ ├── Handposture.msg +│ ├── Handseq.msg +│ ├── Handspeed.msg +│ ├── Handstatus.msg +│ ├── Jointcurrent.msg +│ ├── Jointenflag.msg +│ ├── Jointerrclear.msg +│ ├── Jointerrorcode.msg +│ ├── Jointposeeuler.msg +│ ├── Jointpos.msg +│ ├── Jointposcustom.msg +│ ├── Jointspeed.msg +│ ├── Jointteach.msg +│ ├── Jointtemperature.msg +│ ├── Jointvoltage.msg +│ ├── Liftheight.msg +│ ├── Liftspeed.msg +│ ├── Liftstate.msg +│ ├── Movec.msg +│ ├── Movej.msg +│ ├── Movejp.msg +│ ├── Movel.msg +│ ├── Ortteach.msg +│ ├── Posteach.msg +│ ├── Rmerr.msg +│ ├── Rmplusbase.msg +│ ├── Rmplusstate.msg +│ ├── Setforceposition.msg +│ ├── Setrealtimepush.msg +│ ├── Sixforce.msg +│ └── Stop.msg +├── package.xml #依赖声明文件 +└── src +``` +## rm_ros_interface消息说明 +### 关节错误代码Jointerrorcode_msg +``` +uint16[] joint_error +uint8 dof +``` +__msg成员__ +__uint16[] joint_error__ +每个关节报错信息。 +__uint8 dof__ +机械臂自由度信息。 +### 清除关节错误代码Jointerrclear_msg +``` +uint8 joint_num +``` +__msg成员__ +__joint_num__ +对应关节序号,从基座到机械臂手爪端,序号依次为1-6或1-7。 +### 所有坐标系名称Getallframe_msg +``` +string[10] frame_name +``` +__msg成员__ +__frame_name__ +返回的工作坐标系的名称数组。 +### 关节运动Movej_msg +``` +float32[] joint +uint8 speed +bool block +uint8 trajectory_connect +uint8 dof +``` +__msg成员__ +__joint__ +关节角度,float类型,单位:弧度。 +__speed__ +速度百分比例系数,0-100。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__trajectory_connect__ +#0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +__dof__ +机械臂自由度信息。 +### 直线运动Movel_msg +``` +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect +bool block +``` +__msg成员__ +__pose__ +机械臂位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数(float类型)。 +__speed__ +速度百分比例系数,0-100。 +__trajectory_connect__ +#0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 圆弧运动Movec_msg +``` +geometry_msgs/Pose pose_mid +geometry_msgs/Pose pose_end +uint8 speed +uint8 trajectory_connect +bool block +uint8 loop +``` +__msg成员__ +__pose_mid__ +中间位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。 +__pose_end__ +目标位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。 +__speed__ +速度百分比例系数,0-100。 +__trajectory_connect__ +#0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__loop__ +循环次数 +### 关节空间规划到目标位姿Movejp_msg +``` +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect +bool block +``` +__msg成员__ +__pose__ +目标位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。 +__speed__ +速度百分比例系数,0-100。 +__trajectory_connect__ +#0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 关节示教Jointteach_msg +``` +uint8 num +uint8 direction +uint8 speed +``` +__msg成员__ +__num__ +示教关节的序号,1~7。 +__direction__ +示教方向,0-负方向,1-正方向。 +__speed__ +速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比。 +### 位置示教Posteach_msg +``` +uint8 type +uint8 direction +uint8 speed +``` +__msg成员__ +__type__ +示教类型 输入0:X轴方向 | 1:Y轴方向 | 2:Z轴方向。 +__direction__ +示教方向,0-负方向,1-正方向。 +__speed__ +速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比。 +### 姿态示教Ortteach_msg +``` +uint8 type +uint8 direction +uint8 speed +``` +__msg成员__ +__type__ +示教类型 输入0:RX轴方向 | 1:RY轴方向 | 2:RZ轴方向。 +__direction__ +示教方向,0-负方向,1-正方向。 +__speed__ +速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比。 +### 角度透传Jointpos_msg +``` +float32[] joint +bool follow +float32 expand +uint8 dof +``` +__msg成员__ +__joint__ +关节角度,float类型,单位:弧度。 +__follow__ +跟随状态,bool类型,true高跟随,false低跟随,不设置默认高跟随。 +__expand__ +拓展关节,float类型,单位:弧度。 +__dof__ +机械臂自由度信息。 +### 位姿透传Cartepos_msg +``` +geometry_msgs/Pose pose +bool follow +``` +__msg成员__ +__pose__ +机械臂位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。 +__follow __ +跟随状态,bool类型,true高跟随,false低跟随,不设置默认高跟随。 +### 机械臂当前状态-角度和欧拉角Armoriginalstate_msg +``` +float32[] joint +float32[6] pose +uint16 arm_err +uint16 sys_err +uint8 dof +``` +__msg成员__ +__joint__ +关节角度,float类型,单位:度。 +__pose__ +机械臂当前位姿,float类型,x、y、z坐标,单位:m,x、y、z欧拉角,单位:度。 +__arm_err__ +机械臂运行错误代码,unsigned int类型。 +__arm_err__ +控制器错误代码,unsigned int类型。 +__dof__ +机械臂自由度信息。 +### 机械臂当前状态-弧度和四元数Armstate_msg +``` +float32[] joint +geometry_msgs/Pose pose +uint16 arm_err +uint16 sys_err +uint8 dof +``` +__msg成员__ +__joint__ +关节角度,float类型,单位:弧度。 +__pose__ +机械臂当前位姿,float类型,x、y、z坐标,单位:m,x、y、z、w四元数。 +__arm_err__ +机械臂运行错误代码,unsigned int类型。 +__arm_err__ +控制器错误代码,unsigned int类型。 +__dof__ +机械臂自由度信息。 +### 手爪力控夹取Gripperpick_msg +``` +uint16 speed +uint16 force +bool block +uint16 timeout +``` +__msg成员__ +__speed__ +手爪力控夹取速度,unsigned int类型,范围:1-1000。 +__force__ +手爪夹取力矩阈值,unsigned int类型,范围 :50-1000。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__timeout__ +设置返回超时时间,阻塞模式生效(以秒为单位)。 +### 手爪力控夹取-持续力控夹取Gripperpick_msg +``` +uint16 speed +uint16 force +bool block +uint16 timeout +``` +__msg成员__ +__speed__ +手爪力控夹取速度,unsigned int类型,范围:1-1000。 +__force__ +手爪夹取力矩阈值,unsigned int类型,范围 :50-1000。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__timeout__ +设置返回超时时间,阻塞模式生效(以秒为单位)。 +### 手爪到达指定位置Gripperset_msg +``` +uint16 position +bool block +uint16 timeout +``` +__msg成员__ +__position__ +手爪目标位置,unsigned int类型,范围:1-1000,代表手爪开口度:0-70mm。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__timeout__ +设置返回超时时间,阻塞模式生效(以秒为单位)。 +### 力位混合控制Setforceposition_msg +``` +uint8 sensor +uint8 mode +uint8 direction +int16 n +``` +__msg成员__ +__sensor__ +传感器;0-一维力;1-六维力。 +__mode__ +Mode:0-工作坐标系力控; 1-工具坐标系力控。 +__Direction__ +力控方向;0-沿X 轴;1-沿Y 轴;2-沿 Z 轴;3-沿RX 姿态方向;4-沿 RY 姿态方向;5-沿 RZ 姿态方向。 +__n__ +力的大小,单位 0.1N。 +### 六维力数据Sixforce_msg +``` +float32 force_fx +float32 force_fy +float32 force_fz +float32 force_mx +float32 force_my +float32 force_mz +``` +__msg成员__ +__force_fx__ +沿x轴方向受力大小。 +__force_fy__ +沿y轴方向受力大小。 +__force_fz__ +沿z轴方向受力大小。 +__force_mx__ +沿x轴方向转动受力大小。 +__force_my__ +沿y轴方向转动受力大小。 +__force_mz__ +沿z轴方向转动受力大小。 +### 设置灵巧手手势Handposture_msg +``` +uint16 posture_num +bool block +uint16 timeout +``` +__msg成员__ +__posture_num__ +预先保存在灵巧手内的手势序号,范围:1-40。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__timeout__ +阻塞模式下超时时间设置,单位:秒。 +### 设置灵巧手动作序列Handseq_msg +``` +uint16 seq_num +bool block +uint16 timeout +``` +__msg成员__ +__seq_num__ +预先保存在灵巧手内的序列序号,范围:1-40。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__timeout__ +阻塞模式下超时时间设置,单位:秒。 +### 设置灵巧手各自由度角度Handangle_msg +``` +int16[6] hand_angle +bool block +``` +__msg成员__ +__hand_angle__ +手指角度数组,范围:0-1000。另外,-1 代表该自由度不执行任何操作,保持当前状态。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 设置灵巧手速度Handspeed_msg +``` +uint16 hand_speed +``` +__msg成员__ +__hand_speed__ +手指速度,范围:1-1000。 +### 设置灵巧手力阈值Handforce_msg +``` +uint16 hand_force +``` +__msg成员__ +__hand_force__ +手指力,范围:1-1000。 +### 透传力位混合补偿-角度Forcepositionmovejoint_msg +``` +float32[] joint +uint8 sensor +uint8 mode +int16 dir +float32 force +bool follow +uint8 dof +``` +__msg成员__ +__joint__ +角度力位混合透传,单位:弧度。 +__sensor__ +所使用传感器类型,0-一维力,1-六维力。 +__mode__ +模式,0-沿工作坐标系,1-沿工具端坐标系。 +__dir__ +力控方向,0-5 分别代表 X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z 方向。 +__force__ +力的大小,精度 0.1N 或者 0.1Nm。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +__dof__ +机械臂自由度信息。 +### 透传力位混合补偿-位姿Forcepositionmovejoint_msg +``` +geometry_msgs/Pose pose +uint8 sensor +uint8 mode +int16 dir +float32 force +bool follow +``` +__msg成员__ +__pose__ +机械臂位姿信息,x、y、z位置信息+四元数姿态信息。 +__sensor__ +所使用传感器类型,0-一维力,1-六维力。 +__mode__ +模式,0-沿工作坐标系,1-沿工具端坐标系。 +__dir__ +力控方向,0-5 分别代表 X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z 方向。 +__force__ +力的大小,精度 0.1N 或者 0.1Nm。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 速度开环控制-升降机构Liftspeed_msg +``` +int16 speed +bool block +``` +__msg成员__ +__speed__ +速度百分比,-100-100。Speed < 0:升降机构向下运动;Speed > 0:升降机构向上运动;Speed = 0:升降机构停止运动。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 位置闭环控制-升降机构Liftheight_msg +``` +uint16 height +uint16 speed +bool block +``` +__msg成员__ +__height__ +目标高度,单位 mm,范围:0-2600。 +__speed__ +速度百分比,1-100。 +__block__ +是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 +### 获取升降机构状态-升降机构Liftstate_msg +``` +int16 height +int16 current +uint16 err_flag +``` +__msg成员__ +__height__ +当前升降机构高度,单位:mm,精度:1mm,范围:0-2300。 +__current__ +升降驱动错误代码,错误代码类型参考关节错误代码。 +### 查询或设置UDP机械臂状态主动上报配置Setrealtimepush_msg +``` +uint16 cycle +uint16 port +uint16 force_coordinate +string ip +bool aloha_state_enable +bool arm_current_status_enable +bool expand_state_enable +bool hand_enable +bool joint_speed_enable +bool lift_state_enable +bool plus_base_enable +bool plus_state_enable +``` +__msg成员__ +__cycle__ +设置广播周期,为5ms的倍数。 +__port__ +设置广播的端口号。 +__force_coordinate__ +系统外受力数据的坐标系,0 为传感器坐标系 1 为当前工作坐标系 2 为当前工具坐标系。 +__ip__ +自定义的上报目标IP 地址。 +__aloha_state_enable__ +aloha状态信息主动上报使能。 +__arm_current_status_enable__ +机械臂当前状态主动上报使能。 +__expand_state_enable__ +拓展关节主动上报使能 +__hand_enable__ +灵巧手数据主动上报使能 +__joint_speed_enable__ +关节速度主动上报使能 +__lift_state_enable__ +升降机主动上报使能 +__plus_base_enable__ +末端设备基础信息主动上报使能 +__plus_state_enable__ +末端设备实时信息主动上报使能 +### UDP机械臂状态上报Armcurrentstatus_msg +``` +uint16 arm_current_status +``` +__msg成员__ +__arm_current_status__ +机械臂状态, + 0 - RM_IDLE_E // 使能但空闲状态 + 1 - RM_MOVE_L_E // move L运动中状态 + 2 - RM_MOVE_J_E // move J运动中状态 + 3 - RM_MOVE_C_E // move C运动中状态 + 4 - RM_MOVE_S_E // move S运动中状态 + 5 - RM_MOVE_THROUGH_JOINT_E // 角度透传状态 + 6 - RM_MOVE_THROUGH_POSE_E // 位姿透传状态 + 7 - RM_MOVE_THROUGH_FORCE_POSE_E // 力控透传状态 + 8 - RM_MOVE_THROUGH_CURRENT_E // 电流环透传状态 + 9 - RM_STOP_E // 急停状态 + 10 - RM_SLOW_STOP_E // 缓停状态 + 11 - RM_PAUSE_E // 暂停状态 + 12 - RM_CURRENT_DRAG_E // 电流环拖动状态 + 13 - RM_SENSOR_DRAG_E // 六维力拖动状态 + 14 - RM_TECH_DEMONSTRATION_E // 示教状态 +### UDP关节电流上报Jointcurrent_msg +``` +float32[] joint_current +``` +__msg成员__ +__joint_current__ +当前关节电流,精度 0.001mA。 +### UDP关节使能状态上报Jointenflag_msg +``` +bool[] joint_en_flag +``` +__msg成员__ +__joint_en_flag__ +当前关节使能状态 ,1 为上使能,0 为掉使能。 +### UDP机械臂欧拉角位姿上报Jointposeeuler_msg +``` +float32[3] euler +float32[3] position +``` +__msg成员__ +__euler__ +当前路点姿态欧拉角,精度 0.001rad。 +__position__ +当前路点位置,精度 0.000001M。 +### UDP关节速度上报Jointspeed_msg +``` +float32[] joint_speed +``` +__msg成员__ +__joint_speed__ +当前关节速度,精度0.02RPM。 +### UDP关节温度上报Jointtemperature_msg +``` +float32[] joint_temperature +``` +__msg成员__ +__joint_temperature__ +当前关节温度,精度 0.001℃。 +### UDP关节电压上报Jointvoltage_msg +``` +float32[] joint_voltage +``` +__msg成员__ +__joint_voltage__ +当前关节电压,精度 0.001V。 + +### UDP错误上报Rmerr_msg +``` +uint8 err_len +int32[] err +``` +__msg成员__ +__err_len__ +当前报错数量,uint8。 +__err__ +当前报错代码,int32。 + +### 末端设备基础信息Rmplusbase_msg +``` +string manu # 设备厂家 +int8 type # 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 +string hv # 硬件版本 +string sv # 软件版本 +string bv # boot版本 +int32 id # 设备ID +int8 dof # 自由度 +int8 check # 自检开关 +int8 bee # 蜂鸣器开关 +bool force # 力控支持 +bool touch # 触觉支持 +int8 touch_num # 触觉个数 +int8 touch_sw # 触觉开关 +int8 hand # 手方向 1 :左手 2: 右手 +int32[12] pos_up # 位置上限,单位:无量纲 +int32[12] pos_low # 位置下限,单位:无量纲 +int32[12] angle_up # 角度上限,单位:0.01度 +int32[12] angle_low # 角度下限,单位:0.01度 +int32[12] speed_up # 速度上限,单位:无量纲 +int32[12] speed_low # 速度下限,单位:无量纲 +int32[12] force_up # 力上限,单位:0.001N +int32[12] force_low # 力下限,单位:0.001N +``` +### 末端设备基础信息Rmplusstate_msg +``` +int32 sys_state #系统状态 +int32[12] dof_state #各自由度当前状态 +int32[12] dof_err #各自由度错误信息 +int32[12] pos #各自由度当前位置 +int32[12] speed #各自由度当前速度 +int32[12] angle #各自由度当前角度 +int32[12] current #各自由度当前电流 +int32[18] normal_force #自由度触觉三维力的法向力 +int32[18] tangential_force #自由度触觉三维力的切向力 +int32[18] tangential_force_dir #自由度触觉三维力的切向力方向 +uint32[12] tsa #自由度触觉自接近 +uint32[12] tma #自由度触觉互接近 +int32[18] touch_data #触觉传感器原始数据 +int32[12] force #自由度力矩 +``` + +### 自定义高跟随模式角度透传Jointposcustom_msg +``` +float32[] joint +bool follow +float32 expand +uint8 dof +uint8 trajectory_mode +uint8 radio +``` +__msg成员__ +__joint__ +关节角度,float类型,单位:弧度。 +__follow__ +跟随状态,bool类型,true高跟随,false低跟随,不设置默认高跟随。 +__expand__ +拓展关节,float类型,单位:弧度。 +__dof__ +机械臂自由度信息。 +__trajectory_mode__ +设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。 +__radio__ +设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好。 +### 自定义高跟随模式位姿透传Carteposcustom_msg +``` +geometry_msgs/Pose pose +bool follow +uint8 trajectory_mode +uint8 radio +``` +__msg成员__ +__pose__ +机械臂位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。 +__follow __ +跟随状态,bool类型,true高跟随,false低跟随,不设置默认高跟随。 +__trajectory_mode__ +设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。 +__radio__ +设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好。 + + +主要为套用API实现的一些机械臂本体的功能,其详细介绍和使用在此不详细展开,可以通过专门的文档《[睿尔曼机械臂ROS2话题详细说明](https://github.com/kaola-zero/ros2_rm_robot/blob/main/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)》进行查看。 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armcurrentstatus.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armcurrentstatus.msg new file mode 100755 index 0000000..955c636 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armcurrentstatus.msg @@ -0,0 +1 @@ +uint16 arm_current_status \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armoriginalstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armoriginalstate.msg new file mode 100755 index 0000000..b6f9c7f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armoriginalstate.msg @@ -0,0 +1,6 @@ +float32[] joint +float32[6] pose +uint16 err +uint8 err_len +uint8 dof + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversion.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversion.msg new file mode 100755 index 0000000..66694a0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversion.msg @@ -0,0 +1,14 @@ +string product_version # 机械臂型号 +string controller_version # 机械臂控制器版本,若为四代控制器,则该字段为"4.0" +string algorithm_info # 算法库信息 +Softwarebuildinfo ctrl_info # ctrl 层软件信息 +string dynamic_info # 动力学版本(三代) +Softwarebuildinfo plan_info # plan 层软件信息(三代) +Softwarebuildinfo com_info # communication 模块软件信息(四代) +Softwarebuildinfo program_info # 流程图编程模块软件信息(四代) +bool state # 查询状态 成功true 失败false +string planversion +string ctrlversion +string kernal1 +string kernal2 +string productversion diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv3.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv3.msg new file mode 100755 index 0000000..74f7f6c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv3.msg @@ -0,0 +1,6 @@ +string product_version +string controller_version +string algorithm_info +Softwarebuildinfo ctrl_info +string dynamic_info +Softwarebuildinfo plan_info \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv4.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv4.msg new file mode 100755 index 0000000..9e26a89 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armsoftversionv4.msg @@ -0,0 +1,6 @@ +string product_version +string controller_version +string algorithm_info +Softwarebuildinfo ctrl_info +Softwarebuildinfo com_info +Softwarebuildinfo program_info \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armstate.msg new file mode 100755 index 0000000..4b43eb0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Armstate.msg @@ -0,0 +1,5 @@ +float32[] joint +geometry_msgs/Pose pose +uint16 err +uint8 err_len +uint8 dof diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Cartepos.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Cartepos.msg new file mode 100755 index 0000000..944ef52 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Cartepos.msg @@ -0,0 +1,2 @@ +geometry_msgs/Pose pose +bool follow \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Carteposcustom.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Carteposcustom.msg new file mode 100755 index 0000000..a0f7da0 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Carteposcustom.msg @@ -0,0 +1,4 @@ +geometry_msgs/Pose pose +bool follow +uint8 trajectory_mode +uint8 radio \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Flowchartrunstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Flowchartrunstate.msg new file mode 100755 index 0000000..7f46f63 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Flowchartrunstate.msg @@ -0,0 +1,7 @@ +uint8 run_state # 运行状态 0 未开始 1运行中 2暂停中 +uint8 id # 当前使能的文件id。 +string name # 当前使能的文件名称。 +uint8 plan_speed # 当前使能的文件全局规划速度比例 1-100。 +uint8 step_mode # 单步模式,0为空,1为正常, 2为单步。 +string modal_id # 运行到的流程图块的id。未运行则不返回 +bool state # 查询状态信息 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Force_Position_State.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Force_Position_State.msg new file mode 100755 index 0000000..3da35f4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Force_Position_State.msg @@ -0,0 +1,3 @@ +float32[6] joint +float32 force +uint16 arm_err diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovejoint.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovejoint.msg new file mode 100755 index 0000000..c623cd8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovejoint.msg @@ -0,0 +1,7 @@ +float32[] joint +uint8 sensor +uint8 mode +int16 dir +float32 force +bool follow +uint8 dof \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovepose.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovepose.msg new file mode 100755 index 0000000..9291e01 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Forcepositionmovepose.msg @@ -0,0 +1,6 @@ +geometry_msgs/Pose pose +uint8 sensor +uint8 mode +uint8 dir +int16 force +bool follow \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/GetArmState_Command.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/GetArmState_Command.msg new file mode 100755 index 0000000..d1d74b4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/GetArmState_Command.msg @@ -0,0 +1 @@ +string command diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getallframe.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getallframe.msg new file mode 100755 index 0000000..5192242 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getallframe.msg @@ -0,0 +1 @@ +string[10] frame_name diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getmodbustcpmasterlist.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getmodbustcpmasterlist.msg new file mode 100755 index 0000000..788b6b4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Getmodbustcpmasterlist.msg @@ -0,0 +1,3 @@ +int32 page_num #页码 +int32 page_size #每页大小 +string vague_search #模糊搜索 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gettrajectorylist.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gettrajectorylist.msg new file mode 100755 index 0000000..788b6b4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gettrajectorylist.msg @@ -0,0 +1,3 @@ +int32 page_num #页码 +int32 page_size #每页大小 +string vague_search #模糊搜索 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperpick.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperpick.msg new file mode 100755 index 0000000..9a52534 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperpick.msg @@ -0,0 +1,5 @@ +#手爪以设定的速度力控夹取,当受力超过设定力后,停止运动 +uint16 speed #1~1000,代表手爪开合速度,无量纲 +uint16 force #1~1000,代表手爪夹持力,最大1.5kg +bool block +uint16 timeout #timeout 设置返回超时时间,阻塞模式生效 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperset.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperset.msg new file mode 100755 index 0000000..bc47fc5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Gripperset.msg @@ -0,0 +1,4 @@ +#设置手爪到固定位置,手爪到位置后或者所受力超过阈值后停止 +uint16 position #手爪目标位置,范围:1~1000,代表手爪开口度:0~70mm +bool block +uint16 timeout #timeout 设置返回超时时间,阻塞模式生效 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handangle.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handangle.msg new file mode 100755 index 0000000..d61100b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handangle.msg @@ -0,0 +1,4 @@ +#设置灵巧手角度,灵巧手有 6 个自由度,从 1~6 分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + +int16[6] hand_angle #手指角度数组,范围:0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态 +bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handforce.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handforce.msg new file mode 100755 index 0000000..f1a738f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handforce.msg @@ -0,0 +1,3 @@ +#设置灵巧手关节力阈值 +uint16 hand_force #手指力,范围:1~1000 +#bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handposture.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handposture.msg new file mode 100755 index 0000000..f34b157 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handposture.msg @@ -0,0 +1,4 @@ +#设置灵巧手手势 +uint16 posture_num #预先保存在灵巧手内的手势序号,范围:1~40 +bool block +uint16 timeout #timeout 阻塞模式下超时时间设置,单位:秒 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handseq.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handseq.msg new file mode 100755 index 0000000..3b83ae3 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handseq.msg @@ -0,0 +1,4 @@ +#设置灵巧手动作序列 +uint16 seq_num #预先保存在灵巧手内的序列序号,范围:1~40 +bool block +uint16 timeout #timeout 阻塞模式下超时时间设置,单位:秒 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handspeed.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handspeed.msg new file mode 100755 index 0000000..2a45263 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handspeed.msg @@ -0,0 +1,3 @@ +#设置灵巧手关节速度 +uint16 hand_speed #手指速度,范围:1~1000 +# bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handstatus.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handstatus.msg new file mode 100755 index 0000000..7edbe80 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Handstatus.msg @@ -0,0 +1,5 @@ +uint16[6] hand_angle #手指角度数组,范围:0~2000. +uint16[6] hand_pos #手指位置数组,范围:0~1000. +uint16[6] hand_state #手指状态,0正在松开,1正在抓取,2位置到位停止,3力到位停止,5电流保护停止,6电缸堵转停止,7电缸故障停止 +uint16[6] hand_force #灵巧手自由度电流,单位mN +uint16 hand_err #灵巧手系统错误,1表示有错误,0表示无错误 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointcurrent.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointcurrent.msg new file mode 100755 index 0000000..496e558 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointcurrent.msg @@ -0,0 +1 @@ +float32[] joint_current diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointenflag.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointenflag.msg new file mode 100755 index 0000000..2976aac --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointenflag.msg @@ -0,0 +1 @@ +bool[] joint_en_flag diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrclear.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrclear.msg new file mode 100755 index 0000000..1c906f4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrclear.msg @@ -0,0 +1,3 @@ +#对指定关节进行使能操作 +uint8 joint_num #对应关节序号,从基座到机械臂手爪端,序号依次为1~6 +# bool block #true-阻塞,false-不阻塞 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrorcode.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrorcode.msg new file mode 100755 index 0000000..7ac3d9d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointerrorcode.msg @@ -0,0 +1,2 @@ +uint16[] joint_error #每个关节报错信息 +uint8 dof diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointpos.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointpos.msg new file mode 100755 index 0000000..fc332ef --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointpos.msg @@ -0,0 +1,6 @@ +#control arm joints without planning + +float32[] joint +bool follow +float32 expand +uint8 dof \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposcustom.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposcustom.msg new file mode 100755 index 0000000..b4ca28d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposcustom.msg @@ -0,0 +1,8 @@ +#control arm joints without planning + +float32[] joint +bool follow +float32 expand +uint8 dof +uint8 trajectory_mode +uint8 radio \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposeeuler.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposeeuler.msg new file mode 100755 index 0000000..86a6fb6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointposeeuler.msg @@ -0,0 +1,2 @@ +float32[3] euler +float32[3] position diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointspeed.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointspeed.msg new file mode 100755 index 0000000..9af66de --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointspeed.msg @@ -0,0 +1 @@ +float32[] joint_speed \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointteach.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointteach.msg new file mode 100755 index 0000000..3b58569 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointteach.msg @@ -0,0 +1,4 @@ +uint8 num # 示教关节的序号,1~7 +uint8 direction # 示教方向,0-负方向,1-正方向 +uint8 speed # 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 +# bool block # RM_NONBLOCK0-非阻塞,发送后立即返回;RM_BLOCK1-阻塞,等待控制器返回设置成功指令 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointtemperature.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointtemperature.msg new file mode 100755 index 0000000..a4a89dd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointtemperature.msg @@ -0,0 +1 @@ +float32[] joint_temperature \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointversion.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointversion.msg new file mode 100755 index 0000000..c7fda0c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointversion.msg @@ -0,0 +1,2 @@ +string[7] joint_version # 获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8(三代控制器) +bool state # 获取状态 true获取成功 false获取失败 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointvoltage.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointvoltage.msg new file mode 100755 index 0000000..4c81342 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Jointvoltage.msg @@ -0,0 +1 @@ +float32[] joint_voltage \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftheight.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftheight.msg new file mode 100755 index 0000000..d2d9805 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftheight.msg @@ -0,0 +1,4 @@ +#升降机构运行到指定高度 +uint16 height #目标高度,单位 mm,范围:0~2600 +uint16 speed #速度百分比,1~100 +bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftspeed.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftspeed.msg new file mode 100755 index 0000000..95a959a --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftspeed.msg @@ -0,0 +1,5 @@ +#升降机构速度开环控制 +#Speed < 0:升降机构向下运动 +#Speed > 0:升降机构向上运动 +#Speed = 0:升降机构停止运动 +int16 speed #速度百分比,-100~100 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftstate.msg new file mode 100755 index 0000000..d4baec2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Liftstate.msg @@ -0,0 +1,5 @@ +int16 height #当前高度 +int16 current #当前电流 +uint16 err_flag #驱动错误代码 +int16 mode #当前升降状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 + diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Mastername.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Mastername.msg new file mode 100755 index 0000000..2d3a3b6 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Mastername.msg @@ -0,0 +1 @@ +string master_name # 主站名称 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusreaddata.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusreaddata.msg new file mode 100755 index 0000000..ad1e684 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusreaddata.msg @@ -0,0 +1,2 @@ +int32[] read_data # 读取到的modbus数据 +bool state # 查询状态信息,失败为false,成功true \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtureadparams.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtureadparams.msg new file mode 100755 index 0000000..10440cd --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtureadparams.msg @@ -0,0 +1,4 @@ +int32 address # 数据起始地址 +int32 device # 外设设备地址 +int32 type # 0-控制器端modbus主机;1-工具端modbus主机。 +int32 num # 要读的数据的数量,数据长度不超过109 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtuwriteparams.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtuwriteparams.msg new file mode 100755 index 0000000..2754530 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbusrtuwriteparams.msg @@ -0,0 +1,5 @@ +int32 address # 数据起始地址 +int32 device # 外设设备地址 +int32 type # 0-控制器端modbus主机;1-工具端modbus主机。 +int32 num # 要写的数据的数量,最大不超过100 +int32[] data # 要写的数据,数据长度不超过100 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterinfo.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterinfo.msg new file mode 100755 index 0000000..4575e77 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterinfo.msg @@ -0,0 +1,4 @@ +string master_name # Modbus主站名称,最大长度15个字符,不超过15个字符 +string ip # TCP主站IP地址 +int32 port # TCP主站端口号 +bool state # 查询状态信息,失败为false,成功为true \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterlist.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterlist.msg new file mode 100755 index 0000000..6cbb596 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterlist.msg @@ -0,0 +1,6 @@ +uint8 page_num # 页码 +uint8 page_size # 每页大小 +uint8 total_size # 列表长度 +string vague_search # 模糊搜索 +Modbustcpmasterinfo[] master_list # 返回符合的TCP主站列表 +bool state # 查询状态 成功true 失败false diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterupdata.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterupdata.msg new file mode 100755 index 0000000..5d5a195 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpmasterupdata.msg @@ -0,0 +1,4 @@ +string master_name # Modbus主站名称,最大长度15个字符,不超过15个字符 +string new_master_name # Modbus要更改的主站名称,最大长度15个字符,不超过15个字符 +string ip # TCP主站IP地址 +int32 port # TCP主站端口号 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpreadparams.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpreadparams.msg new file mode 100755 index 0000000..85ec8be --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpreadparams.msg @@ -0,0 +1,5 @@ +int32 address # 数据起始地址 +string master_name # Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) +string ip # 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) +int32 port # 主机连接的端口号 +int32 num # 读取数据数量,最大不超过100 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpwriteparams.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpwriteparams.msg new file mode 100755 index 0000000..ef30e2c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Modbustcpwriteparams.msg @@ -0,0 +1,6 @@ +int32 address # 数据起始地址 +string master_name # Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) +string ip # 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) +int32 port # 主机连接的端口号 +int32 num # 写入数据数量,最大不超过100 +int32[] data # 写入的数据,数据长度不超过100 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movec.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movec.msg new file mode 100755 index 0000000..d58fa08 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movec.msg @@ -0,0 +1,6 @@ +geometry_msgs/Pose pose_mid +geometry_msgs/Pose pose_end +uint8 speed +uint8 trajectory_connect +bool block +uint8 loop \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movej.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movej.msg new file mode 100755 index 0000000..8cbb627 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movej.msg @@ -0,0 +1,5 @@ +float32[] joint +uint8 speed +bool block +uint8 trajectory_connect #0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +uint8 dof diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movejp.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movejp.msg new file mode 100755 index 0000000..82e4fc2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movejp.msg @@ -0,0 +1,4 @@ +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect #0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movel.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movel.msg new file mode 100755 index 0000000..82e4fc2 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Movel.msg @@ -0,0 +1,4 @@ +geometry_msgs/Pose pose +uint8 speed +uint8 trajectory_connect #0 代表立即规划,1 代表和下一条轨迹一起规划,当为 1 时,轨迹不会立即执行 +bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Moveloffset.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Moveloffset.msg new file mode 100755 index 0000000..3411fab --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Moveloffset.msg @@ -0,0 +1,6 @@ +geometry_msgs/Pose pose # 位置姿态偏移,位置单位:米,姿态单位:弧度 +int32 speed # v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 +int32 r # r 轨迹交融半径,目前默认0。 +bool trajectory_connect # trajectory_connect 轨迹连接标志 0:立即规划并执行轨迹,不与后续轨迹连接。1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 +bool frame_type # 参考坐标系类型:0-工作,1-工具 +bool block # 0:非阻塞模式,发送指令后立即返回。1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Ortteach.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Ortteach.msg new file mode 100755 index 0000000..affb36f --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Ortteach.msg @@ -0,0 +1,11 @@ +# ORT_TEACH_MODES type # 示教类型 +# typedef enum +# { +# RX_Rotate = 0, //RX轴方向 +# RY_Rotate = 1, //RY轴方向 +# RZ_Rotate = 2, //RZ轴方向 +# }ORT_TEACH_MODES; +uint8 type # 示教类型 输入0 | 1 | 2 +uint8 direction # 示教方向,0-负方向,1-正方向 +uint8 speed # 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 +# bool block # RM_NONBLOCK0-非阻塞,发送后立即返回;RM_BLOCK1-阻塞,等待控制器返回设置成功指令 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Posteach.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Posteach.msg new file mode 100755 index 0000000..4489033 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Posteach.msg @@ -0,0 +1,11 @@ +# POS_TEACH_MODES type 示教类型 +# typedef enum +# { +# X_Dir = 0, //X轴方向 +# Y_Dir = 1, //Y轴方向 +# Z_Dir = 2, //Z轴方向 +# }POS_TEACH_MODES; +uint8 type # 示教类型 输入0 | 1 | 2 +uint8 direction # 示教方向,0-负方向,1-正方向 +uint8 speed # 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 +# bool block # RM_NONBLOCK0-非阻塞,发送后立即返回;RM_BLOCK1-阻塞,等待控制器返回设置成功指令 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Programrunstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Programrunstate.msg new file mode 100755 index 0000000..32c17f8 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Programrunstate.msg @@ -0,0 +1,10 @@ +int32 run_state # 运行状态 0 未开始 1运行中 2暂停中 +int32 id # 运行轨迹编号 +int32 edit_id # 上次编辑的在线编程编号 id +int32 plan_num # 运行行数 +int32 total_loop # 循环指令数量 +int32 step_mode # 单步模式,1 为单步模式,0 为非单步模式 +int32 plan_speed # 全局规划速度比例 1-100 +int32[] loop_num # 循环行数 +int32[] loop_cont # 对应循环次数 +bool state # 文件下发状态,成功true,失败false \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RS485params.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RS485params.msg new file mode 100755 index 0000000..7a4b649 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RS485params.msg @@ -0,0 +1,3 @@ +int32 mode # 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 +int32 baudrate # 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) +bool state # 查询状态 true查询成功 false查询失败 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmerr.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmerr.msg new file mode 100755 index 0000000..95ed53b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmerr.msg @@ -0,0 +1,2 @@ +uint8 err_len +int32[] err \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusbase.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusbase.msg new file mode 100755 index 0000000..892d04b --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusbase.msg @@ -0,0 +1,22 @@ +string manu # 设备厂家 +int8 type # 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 +string hv # 硬件版本 +string sv # 软件版本 +string bv # boot版本 +int32 id # 设备ID +int8 dof # 自由度 +int8 check # 自检开关 +int8 bee # 蜂鸣器开关 +bool force # 力控支持 +bool touch # 触觉支持 +int8 touch_num # 触觉个数 +int8 touch_sw # 触觉开关 +int8 hand # 手方向 1 :左手 2: 右手 +int32[12] pos_up # 位置上限,单位:无量纲 +int32[12] pos_low # 位置下限,单位:无量纲 +int32[12] angle_up # 角度上限,单位:0.01度 +int32[12] angle_low # 角度下限,单位:0.01度 +int32[12] speed_up # 速度上限,单位:无量纲 +int32[12] speed_low # 速度下限,单位:无量纲 +int32[12] force_up # 力上限,单位:0.001N +int32[12] force_low # 力下限,单位:0.001N diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusstate.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusstate.msg new file mode 100755 index 0000000..7c35522 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmplusstate.msg @@ -0,0 +1,14 @@ +int32 sys_state #系统状态 +int32[12] dof_state #各自由度当前状态 +int32[12] dof_err #各自由度错误信息 +int32[12] pos #各自由度当前位置 +int32[12] speed #各自由度当前速度 +int32[12] angle #各自由度当前角度 +int32[12] current #各自由度当前电流 +int32[18] normal_force #自由度触觉三维力的法向力 +int32[18] tangential_force #自由度触觉三维力的切向力 +int32[18] tangential_force_dir #自由度触觉三维力的切向力方向 +uint32[12] tsa #自由度触觉自接近 +uint32[12] tma #自由度触觉互接近 +int32[18] touch_data #触觉传感器原始数据 +int32[12] force #自由度力矩 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmversion.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmversion.msg new file mode 100755 index 0000000..0b62608 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Rmversion.msg @@ -0,0 +1 @@ +string version \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RobotInfo.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RobotInfo.msg new file mode 100755 index 0000000..8301851 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/RobotInfo.msg @@ -0,0 +1,12 @@ +# 机械臂自由度(关节数量) +uint8 arm_dof +# 机械臂型号 +# 示例:0=RM_65, 1=RM_75, 2=RML_63I(已弃用), 3=RML_63II,4=RML_63III,5=ECO_65,6=ECO_62,7=GEN_72,8=ECO63,9=通用机器人 +uint8 arm_model +# 末端力传感器版本 +# 示例:0=标准版, 1=一维力版, 2=六维力版, 3=一体化六维力版 +uint8 force_type +# 机械臂控制器版本(3:三代,4:四代) +uint8 robot_controller_version +# 是否读取成功 +bool state diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sendproject.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sendproject.msg new file mode 100755 index 0000000..8b7b447 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sendproject.msg @@ -0,0 +1,8 @@ +string project_path # 下发文件路径文件名 +int32 project_path_len # 名称长度 +int32 plan_speed # 规划速度比例系数 +int32 only_save # 0-保存并运行文件,1-仅保存文件,不运行 +int32 save_id # 保存到控制器中的编号 +int32 step_flag # 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式 +int32 auto_start # 设置默认在线编程文件,1-设置默认 0-设置非默认 +int32 project_type # 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件 \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setforceposition.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setforceposition.msg new file mode 100755 index 0000000..99e54e5 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setforceposition.msg @@ -0,0 +1,5 @@ +uint8 sensor +uint8 mode +uint8 direction +int16 n +# bool block \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setrealtimepush.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setrealtimepush.msg new file mode 100755 index 0000000..b4d059e --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Setrealtimepush.msg @@ -0,0 +1,12 @@ +uint16 cycle +uint16 port +uint16 force_coordinate +string ip +bool aloha_state_enable +bool arm_current_status_enable +bool expand_state_enable +bool hand_enable +bool joint_speed_enable +bool lift_state_enable +bool plus_base_enable +bool plus_state_enable \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sixforce.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sixforce.msg new file mode 100755 index 0000000..d859fd4 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Sixforce.msg @@ -0,0 +1,6 @@ +float32 force_fx +float32 force_fy +float32 force_fz +float32 force_mx +float32 force_my +float32 force_mz \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Softwarebuildinfo.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Softwarebuildinfo.msg new file mode 100755 index 0000000..15cb68d --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Softwarebuildinfo.msg @@ -0,0 +1,2 @@ +string build_time +string version \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Stop.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Stop.msg new file mode 100755 index 0000000..42718e7 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Stop.msg @@ -0,0 +1 @@ +bool state #true: 急停 false:恢复 diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Toolsoftwareversionv4.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Toolsoftwareversionv4.msg new file mode 100755 index 0000000..1d80939 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Toolsoftwareversionv4.msg @@ -0,0 +1,2 @@ +string tool_version # 末端版本 +bool state # 查询状态,成功返回true,失败返回false \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectoryinfo.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectoryinfo.msg new file mode 100755 index 0000000..7fb390c --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectoryinfo.msg @@ -0,0 +1,4 @@ +string name #轨迹名称 +string create_time #创建时间 +int32 point_num #轨迹点数量 +bool state #查询状态 成功true 失败false \ No newline at end of file diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectorylist.msg b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectorylist.msg new file mode 100755 index 0000000..9c03500 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/msg/Trajectorylist.msg @@ -0,0 +1,6 @@ +int32 page_num # 页码 +int32 page_size # 每页大小 +int32 total_size # 列表长度 +string vague_search # 模糊搜索 +Trajectoryinfo[] tra_list # 返回符合的轨迹列表 +bool state # 查询状态 成功true 失败false diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/package.xml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/package.xml new file mode 100755 index 0000000..01b2649 --- /dev/null +++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_ros_interfaces/package.xml @@ -0,0 +1,22 @@ + + + + rm_ros_interfaces + 0.0.0 + TODO: Package description + rm + TODO: License declaration + + ament_cmake + rosidl_default_generators + std_msgs + geometry_msgs + rosidl_default_runtime + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + ament_cmake + +