Browse Source

2024-1-16

bzx 4 months ago
parent
commit
c4fdfe1034
73 changed files with 4584 additions and 0 deletions
  1. 1 0
      catkin_ws/.catkin_workspace
  2. 224 0
      catkin_ws/src/lst_robot_r/CMakeLists.txt
  3. 51 0
      catkin_ws/src/lst_robot_r/README.md
  4. 475 0
      catkin_ws/src/lst_robot_r/hanqiangpose.py
  5. 5 0
      catkin_ws/src/lst_robot_r/launch/start.launch
  6. 7 0
      catkin_ws/src/lst_robot_r/msg/JointTrajectoryPoint_ex.msg
  7. 3 0
      catkin_ws/src/lst_robot_r/msg/JointTrajectory_ex.msg
  8. 70 0
      catkin_ws/src/lst_robot_r/package.xml
  9. 50 0
      catkin_ws/src/lst_robot_r/scripts/command.py
  10. 153 0
      catkin_ws/src/lst_robot_r/scripts/dycl_0506.py
  11. 259 0
      catkin_ws/src/lst_robot_r/scripts/hjsx.py
  12. 561 0
      catkin_ws/src/lst_robot_r/scripts/moveitServer2.py
  13. 45 0
      catkin_ws/src/lst_robot_r/scripts/redis_publisher.py
  14. 126 0
      catkin_ws/src/lst_robot_r/scripts/start.py
  15. 49 0
      catkin_ws/src/visual/CMakeLists.txt
  16. 68 0
      catkin_ws/src/visual/package.xml
  17. 251 0
      catkin_ws/src/visual/src/visual_tools.cpp
  18. 11 0
      catkin_ws/src/yunhua_1006a_moveit_config/.setup_assistant
  19. 10 0
      catkin_ws/src/yunhua_1006a_moveit_config/CMakeLists.txt
  20. 5 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/cartesian_limits.yaml
  21. 18 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/chomp_planning.yaml
  22. 13 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/fake_controllers.yaml
  23. 4 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/gazebo_controllers.yaml
  24. 292 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/gazebo_yunhua_ryhj.urdf
  25. 40 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/joint_limits.yaml
  26. 7 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/kinematics.yaml
  27. 198 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/ompl_planning.yaml
  28. 0 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/ros_controllers.yaml
  29. 9 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/sensors_3d.yaml
  30. 2 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/simple_moveit_controllers.yaml
  31. 39 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/stomp_planning.yaml
  32. 57 0
      catkin_ws/src/yunhua_1006a_moveit_config/config/yunhua_ryhj.srdf
  33. 21 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/chomp_planning_pipeline.launch.xml
  34. 15 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/default_warehouse_db.launch
  35. 66 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/demo.launch
  36. 21 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/demo_gazebo.launch
  37. 12 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/fake_moveit_controller_manager.launch.xml
  38. 34 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/gazebo.launch
  39. 17 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/joystick_control.launch
  40. 105 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/move_group.launch
  41. 378 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/moveit.rviz
  42. 15 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/moveit_rviz.launch
  43. 20 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml
  44. 24 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/ompl_planning_pipeline.launch.xml
  45. 15 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
  46. 26 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/planning_context.launch
  47. 10 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/planning_pipeline.launch.xml
  48. 4 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml
  49. 11 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/ros_controllers.launch
  50. 21 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/run_benchmark_ompl.launch
  51. 17 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/sensor_manager.launch.xml
  52. 16 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/setup_assistant.launch
  53. 8 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/simple_moveit_controller_manager.launch.xml
  54. 23 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/stomp_planning_pipeline.launch.xml
  55. 23 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/trajectory_execution.launch.xml
  56. 15 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/warehouse.launch
  57. 16 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/warehouse_settings.launch.xml
  58. 3 0
      catkin_ws/src/yunhua_1006a_moveit_config/launch/yunhua_ryhj_moveit_sensor_manager.launch.xml
  59. 41 0
      catkin_ws/src/yunhua_1006a_moveit_config/package.xml
  60. 14 0
      catkin_ws/src/yunhua_ryhj/CMakeLists.txt
  61. 1 0
      catkin_ws/src/yunhua_ryhj/config/joint_names_yunhua_ryhj.yaml
  62. 20 0
      catkin_ws/src/yunhua_ryhj/launch/display.launch
  63. 20 0
      catkin_ws/src/yunhua_ryhj/launch/gazebo.launch
  64. BIN
      catkin_ws/src/yunhua_ryhj/meshes/base_link.STL
  65. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link1.STL
  66. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link2.STL
  67. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link3.STL
  68. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link4.STL
  69. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link5.STL
  70. BIN
      catkin_ws/src/yunhua_ryhj/meshes/link6.STL
  71. 21 0
      catkin_ws/src/yunhua_ryhj/package.xml
  72. 8 0
      catkin_ws/src/yunhua_ryhj/urdf/yunhua_ryhj.csv
  73. 420 0
      catkin_ws/src/yunhua_ryhj/urdf/yunhua_ryhj.urdf

+ 1 - 0
catkin_ws/.catkin_workspace

@@ -0,0 +1 @@
+# This file currently only serves to mark the location of a catkin workspace for tool integration

+ 224 - 0
catkin_ws/src/lst_robot_r/CMakeLists.txt

@@ -0,0 +1,224 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(lst_robot_r)
+
+## 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(catkin REQUIRED COMPONENTS
+  roscpp
+  rospy
+  std_msgs
+  message_generation
+)
+
+## System dependencies are found with CMake's conventions
+# find_package(Boost REQUIRED COMPONENTS system)
+
+
+## Uncomment this if the package has a setup.py. This macro ensures
+## modules and global scripts declared therein get installed
+## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
+# catkin_python_setup()
+
+################################################
+## Declare ROS messages, services and actions ##
+################################################
+
+## To declare and build messages, services or actions from within this
+## package, follow these steps:
+## * Let MSG_DEP_SET be the set of packages whose message types you use in
+##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
+## * In the file package.xml:
+##   * add a build_depend tag for "message_generation"
+##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
+##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
+##     but can be declared for certainty nonetheless:
+##     * add a exec_depend tag for "message_runtime"
+## * In this file (CMakeLists.txt):
+##   * add "message_generation" and every package in MSG_DEP_SET to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * add "message_runtime" and every package in MSG_DEP_SET to
+##     catkin_package(CATKIN_DEPENDS ...)
+##   * uncomment the add_*_files sections below as needed
+##     and list every .msg/.srv/.action file to be processed
+##   * uncomment the generate_messages entry below
+##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
+
+## Generate messages in the 'msg' folder
+add_message_files(
+   FILES
+   JointTrajectoryPoint_ex.msg
+   JointTrajectory_ex.msg
+   
+ )
+
+## Generate services in the 'srv' folder
+# add_service_files(
+#   FILES
+#   Service1.srv
+#   Service2.srv
+# )
+
+## Generate actions in the 'action' folder
+# add_action_files(
+#   FILES
+#   Action1.action
+#   Action2.action
+# )
+
+## Generate added messages and services with any dependencies listed here
+ generate_messages(
+   DEPENDENCIES
+   std_msgs
+ )
+
+################################################
+## Declare ROS dynamic reconfigure parameters ##
+################################################
+
+## To declare and build dynamic reconfigure parameters within this
+## package, follow these steps:
+## * In the file package.xml:
+##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
+## * In this file (CMakeLists.txt):
+##   * add "dynamic_reconfigure" to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * uncomment the "generate_dynamic_reconfigure_options" section below
+##     and list every .cfg file to be processed
+
+## Generate dynamic reconfigure parameters in the 'cfg' folder
+# generate_dynamic_reconfigure_options(
+#   cfg/DynReconf1.cfg
+#   cfg/DynReconf2.cfg
+# )
+
+###################################
+## catkin specific configuration ##
+###################################
+## The catkin_package macro generates cmake config files for your package
+## Declare things to be passed to dependent projects
+## INCLUDE_DIRS: uncomment this if your package contains header files
+## LIBRARIES: libraries you create in this project that dependent projects also need
+## CATKIN_DEPENDS: catkin_packages dependent projects also need
+## DEPENDS: system dependencies of this project that dependent projects also need
+catkin_package(
+#  INCLUDE_DIRS include
+#  LIBRARIES lstrobot_planning
+CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
+#  DEPENDS system_lib
+
+)
+
+###########
+## Build ##
+###########
+
+## Specify additional locations of header files
+## Your package locations should be listed before other locations
+include_directories(
+include_directories(include ${catkin_INCLUDE_DIRS} )
+
+# include
+  ${catkin_INCLUDE_DIRS}
+)
+
+## Declare a C++ library
+# add_library(${PROJECT_NAME}
+#   src/${PROJECT_NAME}/lstrobot_planning.cpp
+# )
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Declare a C++ executable
+## With catkin_make all packages are built within a single CMake context
+## The recommended prefix ensures that target names across packages don't collide
+# add_executable(${PROJECT_NAME}_node src/lstrobot_planning_node.cpp)
+
+## Rename C++ executable without prefix
+## The above recommended prefix causes long target names, the following renames the
+## target back to the shorter version for ease of user use
+## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
+# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
+
+## Add cmake target dependencies of the executable
+## same as for the library above
+# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Specify libraries to link a library or executable target against
+# target_link_libraries(${PROJECT_NAME}_node
+#   ${catkin_LIBRARIES}
+# )
+
+#############
+## Install ##
+#############
+
+# all install targets should use catkin DESTINATION variables
+# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
+
+## Mark executable scripts (Python etc.) for installation
+## in contrast to setup.py, you can choose the destination
+ catkin_install_python(PROGRAMS
+   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+ )
+
+## Mark executables for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
+# install(TARGETS lstrobot_planning_node
+#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark libraries for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
+# install(TARGETS set_update
+#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
+# )
+
+## Mark cpp header files for installation
+# install(DIRECTORY include/${PROJECT_NAME}/
+#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+#   FILES_MATCHING PATTERN "*.h"
+#   PATTERN ".svn" EXCLUDE
+# )
+
+## Mark other files for installation (e.g. launch and bag files, etc.)
+# install(FILES
+#   # myfile1
+#   # myfile2
+#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+# )
+install(DIRECTORY launch 
+    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+  )
+
+#############
+## Testing ##
+#############
+
+## Add gtest based cpp test target and link libraries
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_lstrobot_planning.cpp)
+# if(TARGET ${PROJECT_NAME}-test)
+#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
+# endif()
+
+## Add folders to be run by python nosetests
+# catkin_add_nosetests(test)
+
+# add_executable(set_update scripts/set_update_paramter_p.py)
+#set_target_properties(moveit_cartesian_demo PROPERTIES LINKER_LANGUAGE PYTHON)
+
+#add_executable(add_objects src/add_objects.cpp)
+#add_dependencies(add_objects ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+#target_link_libraries(add_obje
+#	${catkin_LIBRARIES}
+#	${OpenCV_LIBRARIES}
+#	${PCL_LIBRARIES}
+#)

+ 51 - 0
catkin_ws/src/lst_robot_r/README.md

@@ -0,0 +1,51 @@
+## README
+### 1.运行代码
+1. source工作空间
+2. sudo chmod +x *.py文件
+3. roslaunch lst_robot_r start.launch
+
+### 2.package(SRC)
+1. **lst_robot_r**  
+1.1 **launch**-launch启动文件  
+2.2 **msg**-自定义消息  
+3.3 **scripts**-Python代码  
+
+2. **a9**  
+2.1 **config**-机械臂先关配置文件  
+2.2 **launch**-launch启动文件  
+2.3 **meshes**-机械臂STL文件  
+2.4 **urdf**-机械臂urdf模型  
+
+3. **robot_config**  
+3.1 **config**-moveit配置文件,常用srdf(修改机器人配置)  
+3.2 **launch**-launch启动文件,包括demo.launch文件  
+
+4. **Data**  
+4.1 点云数据,起始点终点数据,导出的其他的数据(轨迹关节值、末端执行器笛卡尔坐标)  
+
+5. **visual**  
+5.1 规划结果可视化  
+
+## 2024.9.30
+- 添加修改笛卡尔路径参数的函数(速度,加速度)
+- 修正机械臂的初始姿态(home位姿)
+- 修改焊接姿态,固定焊接位姿
+
+## 2024.10.12
+- 增加点云数据,起始点终点数据,测试碰撞检测
+
+## 2024.10.17
+- 修改规划逻辑(简单避障),规划完一条焊缝后,末端执行器向上移动0.1m,然后继续规划下一条焊缝
+- 修改urdf关节运动范围为FAUNC m10iA-8L实际运动范围  
+
+## 2024.10.29
+- 配置机械臂moveit_config文件
+- 修改仿真模型为fanuc_m10iA/8l
+- 更新2024-9-23-L/try分支代码为最新
+
+## 2024.10.30
+- 待完成:尝试使用plan()代替compute_cartesian_path(),来进行全局避障规划(会出现翻转的情况,应该是初始位姿的问题)
+- 待完成:尝试使用OMPL-CHOMP规划适配器进行规划,即前端使用OMPL获得初始路径,后端使用CHOMP对路径进行优化,提高精度和避障效果
+
+## 2024.10.31(hjsx.py)
+- 修改焊接顺序,使得两条平行焊缝的焊接方向相同

+ 475 - 0
catkin_ws/src/lst_robot_r/hanqiangpose.py

@@ -0,0 +1,475 @@
+import numpy as np
+from scipy.spatial.transform import Rotation as R
+import open3d as o3d
+from scipy.spatial import KDTree
+import tf.transformations as tft
+import os
+import rospy
+from math import acos,tan,atan,degrees,sqrt
+
+def corner_angle_discrimination(point,data,fangxiang):#角落角度鉴定
+    # 构建KDTree索引
+    tree = KDTree(data)
+    indices = np.array(tree.query_ball_point(point, r=30, p=2)) # 返回这些点的索引数组
+    distances = np.array([np.linalg.norm(point - data[index]) for index in indices])
+    distance_filter = distances >= 10
+    filtered_indices = indices[distance_filter]
+    data_circular = data[filtered_indices]
+
+    # 可视化
+    # pt_cloud_circular = o3d.geometry.PointCloud()
+    # pt_cloud_circular.points = o3d.utility.Vector3dVector(data_circular)
+    # o3d.visualization.draw_geometries([pt_cloud_circular])
+
+    # 获取与方向向量相似的点云
+    data_similar = []
+    for i in range(len(data_circular)):
+        v = np.array(data_circular[i]) - point
+        angle = acos(np.dot(v, fangxiang) / (np.linalg.norm(v) * np.linalg.norm(fangxiang)))#求向量夹角
+        angle_deg = degrees(angle)#弧度转角度?
+        if angle_deg <= 15:
+            data_similar.append(data_circular[i])
+    
+    if len(data_similar) >= 1:
+        corner = True
+    else:
+        corner = False
+    return corner
+
+def set_yaw_angle(R_mat,yaw):
+    #旋转矩阵  X  Z
+    pz1 = np.array([[1, 0, 0],
+                    [0, np.cos(yaw), -np.sin(yaw)],
+                    [0, np.sin(yaw),  np.cos(yaw)]])
+    
+    Z_PI = np.array([[np.cos(np.pi), -np.sin(np.pi), 0],
+                    [np.sin(np.pi), np.cos(np.pi), 0],
+                    [0, 0, 1]])
+    R1_mat = np.matmul(R_mat,pz1)
+    
+    sign = check_x_axis_direction(R1_mat)
+    if sign == 1:
+        pass
+    elif sign == -1:
+        R1_mat = np.matmul(R1_mat, Z_PI)
+
+    q = R.from_matrix(R1_mat).as_quat()
+    q = q.tolist()  # 将NumPy数组转换为列表
+    return q
+
+def calculate_angle_with_xy_plane(point1,point2):
+    # 计算方向向量
+    dir_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], point2[2] - point1[2]])
+    
+    # 计算方向向量在 xy 平面上的投影
+    proj_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], 0])
+    
+    # 计算夹角
+    angle = acos(np.dot(dir_vector, proj_vector) / (np.linalg.norm(dir_vector) * np.linalg.norm(proj_vector)))
+    angle_deg = degrees(angle)
+
+    return angle_deg
+def check_x_axis_direction(rotation_matrix):
+    # 提取旋转后的 x 轴方向向量
+    x_prime = rotation_matrix[:, 0]
+    # 检查 x 轴的 z 分量
+    if x_prime[2] > 0:
+        return 1
+    elif x_prime[2] < 0:
+        return -1
+    else:
+        return 0
+    
+def load_point_cloud_from_txt(file_path):
+    """导入点云数据"""
+    points = []
+    with open(file_path, 'r') as file:
+        for line in file:
+            # 假设每一行是“x y z”格式,没有多余空格
+            coordinates = line.strip().split()
+            if len(coordinates) == 3:  # 检查是否为有效的三维点
+                point = [float(coord) for coord in coordinates]
+                points.append(point)
+
+    return np.array(points)
+
+def load_point_cloud_from_binary_txt(file_path):
+    with open(file_path, 'rb') as f:
+        binary_data = f.read()
+
+        # 将二进制数据转换为 NumPy 数组
+        point_cloud = np.frombuffer(binary_data, dtype=np.float64).reshape(-1, 3)
+    return point_cloud
+
+def get_hanfeng(file_path):
+    """从文件中读取焊缝起点、终点 计算中间点,并计算两点构成的向量"""
+    with open(file_path, 'r') as file:
+        # 逐行读取文件内容
+        lines = file.readlines()#一次读入 每行对应列表一个元素
+    start_points, end_points, midpoints , hanfeng = [],[],[],[]
+    for line in lines:
+        # 去除行尾的换行符并按'/'分割每一行
+        points_str = line.strip().split('/')
+        
+        # 确保每一行都正确地分为两部分
+        if len(points_str) == 2:
+            point1_str = points_str[0].split(',')
+            point2_str = points_str[1].split(',')
+            
+            # 转换字符串为浮点数列表,构造三维点
+            point1 = [float(coord) for coord in point1_str]
+            point2 = [float(coord) for coord in point2_str]
+
+            midpoint = [(p2 + p1)/2 for p1, p2 in zip(point1, point2)]#计算两点的中点
+            vector = [p2 - p1 for p1, p2 in zip(point1, point2)]#计算向量 终点-起点=起点指向终点的向量?
+            
+            start_points.append(point1)
+            end_points.append(point2)
+            midpoints.append(midpoint)  
+            hanfeng.append(vector)   
+
+    return start_points, end_points, midpoints, hanfeng
+
+def compute_Rc2w_tc2w(file_path_Tw2c):#d读 Tw2c.txt 一个4x4矩阵?
+    """相机和基底坐标系的转换关系"""
+    # 读取文件
+    with open(file_path_Tw2c, 'r') as file:
+        lines = file.readlines()
+
+    lines = [line.strip().replace('[', '').replace(']', '').split() for line in lines]#
+    data = [[float(num) for num in line] for line in lines]
+    data = np.array(data)
+    # 提取Rw2c和tw2c
+    Rw2c = data[:3,:3]#3x3部分
+    tw2c = data[:3,-1]#三行四列部分  没有写成列向量??? python 转置都一样?
+
+    # print("RW2c")
+    # print(Rw2c)
+    # print("tw2c")
+    # print(tw2c)
+    # print(tw2c.T)
+    Rc2w = Rw2c.T#求转置矩阵
+    tc2w = -np.matmul(Rc2w, tw2c)#计算矩阵乘积
+    
+    return Rc2w,tc2w
+
+def compute_pose_R(fangxiang, hanfeng,start_point, end_point):
+    """wg根据计算出的焊接时z轴负方向的向量(fangxiang)和由起点指向终点的向量(hanfeng)计算旋转矩阵""" #得到的是fangxiang向量相对于基坐标系原点的姿态变换矩阵 多了个绕x转180的变换
+    x, y, z = fangxiang
+
+    # 计算旋转角度
+    rotx = -np.arctan2(y, z)#投影到yz平面的的夹角
+    roty = np.arctan2(x, np.sqrt(y**2 + z**2))#向量和yz面的夹角
+
+    # 构造旋转矩阵 rot x y   先绕x转不影响向量和yz面的夹角?
+    A = np.array([[1, 0, 0],
+                [0, np.cos(rotx), -np.sin(rotx)],
+                [0, np.sin(rotx), np.cos(rotx)]])
+    
+    B = np.array([[np.cos(roty), 0, np.sin(roty)],
+                [0, 1, 0],
+                [-np.sin(roty), 0, np.cos(roty)]])
+    
+    bb = np.matmul(hanfeng, np.matmul(A, B))#先转到XOZ  再转到X  相当于通过将方向向量转到z轴上的方式 让焊缝向量转到XOY平面 通过方向向量和焊缝向量的正交关系求出向量在Z轴上的转角
+    # 区分平缝竖缝
+    angle = calculate_angle_with_xy_plane(start_point,end_point)#计算起始点的向量与xy平面的夹角
+    ispingfeng = abs(angle) < 30
+    if ispingfeng: #一个是y起转 一个是x起转  差90度  不然竖缝的话焊枪就朝向两面开口方向  差90度就是能够向上的同时朝向开口方向
+        rotz = np.arctan2(bb[0], -bb[1])
+    else:
+        rotz = np.arctan2(bb[1], bb[0])
+    # 构造旋转矩阵 rot z x
+    C = np.array([[np.cos(rotz), -np.sin(rotz), 0],
+                [np.sin(rotz), np.cos(rotz), 0],
+                [0, 0, 1]])
+    D = np.array([[1, 0, 0],
+                    [0, np.cos(np.pi), -np.sin(np.pi)],
+                    [0, np.sin(np.pi), np.cos(np.pi)]])
+
+    R_mat = np.matmul(A, np.matmul(B, np.matmul(C, D)))
+    #A*(B*(C*D))              x*y*z*x(180)
+    return R_mat, ispingfeng
+#TODO 
+def get_quaternion(data, midpoint, hanfeng, start_point, end_point,result_ping,result_shu,result_wai,file_path_Tw2c): 
+
+    # 构建KDTree索引
+    tree = KDTree(data)
+    # 查询半径范围内的点,找出"data"中所有距离"midpoint"点在r以内的点,这里使用的是欧几里得距离(由p=2表示)
+    indices = np.array(tree.query_ball_point(midpoint, r=30, p=2)) #返回这些点相对tree的索引数组
+    distances = np.array([np.linalg.norm(midpoint - data[index]) for index in indices])#距离数组:内容为计算中点到刚刚搜索到的点的距离
+    # 对numpy数组进行布尔索引
+    # distance_filter = np.logical_and(distances >= 10, distances <= 50)
+    distance_filter = distances >= 10#返回 distances 中符合条件的元素的下标的列表
+    # 使用布尔索引过滤出符合条件的索引
+    filtered_indices = indices[distance_filter]#根据布尔索引 从 distance_filter 返回indices对应元素的列表 也就是符合条件的点的下标
+    # 提取符合条件的点
+    data_circular = data[filtered_indices]#
+
+    #以上步骤筛选点云中距离 midpoint(焊缝向量的中点) 周围半径r=30内的所有点 并再次筛选出这些点到 midpoint 的距离大于10的点
+
+    # 可视化
+    # pt_cloud_circular = o3d.geometry.PointCloud()
+    # pt_cloud_circular.points = o3d.utility.Vector3dVector(data_circular)
+    # o3d.visualization.draw_geometries([pt_cloud_circular])
+
+    # 获取焊缝竖直方向上的点云
+    data_shu = []
+    for i in range(len(data_circular)):#遍历刚刚筛选出的点
+        P = np.array(data_circular[i])#从点集提取点
+        v = P - midpoint  #与中点作差
+        anglecos = np.dot(v, hanfeng) / (np.linalg.norm(v) * np.linalg.norm(hanfeng))#利用点积公式得到cos值
+        
+        if abs(anglecos) <= 0.015:#如果cos<=0.015 也就是角度 >=89.14
+            # print(anglecos)
+            data_shu.append(P)
+    data_shu = np.array(data_shu)
+    # # 可视化
+    # pt_cloud_shu = o3d.geometry.PointCloud()
+    # pt_cloud_shu.points = o3d.utility.Vector3dVector(np.array(data_shu))
+    # o3d.visualization.draw_geometries([pt_cloud_shu])
+
+    #至此 获取了刚刚提取的  10<r<30 的点云中 垂直于中点为起点的 垂直方向的点云(一个小半扇形)
+ ##################################################
+ ##################################################
+    random_point = data_shu[np.random.randint(0, len(data_shu))]#获取data中任意一点
+    # 与midpoint一起定义直线向量
+    nohanfeng = random_point - midpoint  #data_shu中任意一点midpoint构成的向量,计算所有点和该向量的距离判断是否是外缝(只拍到一面)
+
+    distances_to_line = []  #
+
+    for i in range(data_shu.shape[0]):  # 遍历每一个点 P
+        P = data_shu[i]
+        A = midpoint
+        u = nohanfeng
+        v = P - A
+        distance = np.linalg.norm(np.cross(u, v)) / np.linalg.norm(u)#得到v的终点离u的垂直距离  向量叉乘
+        distances_to_line.append(distance)
+
+    distances_to_line = np.array(distances_to_line)
+
+    all_distances_less_than_10 = np.all(distances_to_line < 5)#都小于10为true,也就是 data_shu 只有一列,侧着拍得外缝
+    #如果距离都小于10说明 在焊缝向量中点10<r<30的球体内 取的所有的垂直焊缝的点都在同一平面上也就是说点云只有焊缝的其中一个面  只有侧着拍外缝或某种角度拍内缝才会出现
+    if all_distances_less_than_10:#就只有一个面
+        # 随机选取data_shu中的第一个点
+        random_index = np.random.randint(0, data_shu.shape[0])
+        vector1 = data_shu[random_index] - midpoint
+        vector1 /= np.linalg.norm(vector1)  # 单位化vector1
+        fa_xian = np.cross(vector1, hanfeng)
+        fa_xian /= np.linalg.norm(fa_xian) #得到垂直于仅仅拍到的一面的法向量的单位向量
+
+        point = []
+        point1 = midpoint + 50 * fa_xian#应该是取法向量上距离 midpoint 为50的两个点
+        point2 = midpoint - 50 * fa_xian
+
+        Rc2w,tc2w = compute_Rc2w_tc2w(file_path_Tw2c)#取获取的相机与基坐标系矩阵的逆解
+
+        point1_c = np.matmul(Rc2w, point1) + tc2w#矩阵相乘 再相加 得到基坐标系下焊缝点到 相机坐标系下的描述
+        point2_c = np.matmul(Rc2w, point2) + tc2w
+
+        a = np.linalg.norm(point1_c)#求长度
+        b = np.linalg.norm(point2_c)      
+
+        if a < b:#取离相机更近的端点
+            point = point1
+        else:
+            point = point2
+
+        faxian = point - midpoint
+        vector2 =  faxian / np.linalg.norm(faxian)  # 单位化vector2  选取朝向相机的一面的朝向为法向量方向???
+
+        fangxiang = vector1  + vector2*1.2 #得到焊接方向?  1:1.2是 与法向量所垂直平面 50°
+
+        R_mat, ispingfeng = compute_pose_R(fangxiang, hanfeng, start_point, end_point)#应该是焊缝向量到焊枪位姿的转换(焊枪位姿和焊接方向fangxiang是相反的方向)?
+        if ispingfeng:#左右歪的角度---平缝绕焊枪的x转  竖缝绕焊枪的y转  应该都是右乘 相对于自己的轴转  
+            ##偏转矩阵 x  x  z  ##
+            pz1 = np.array([[1, 0, 0],
+                        [0, np.cos(yaw), -np.sin(yaw)],
+                        [0, np.sin(yaw),  np.cos(yaw)]])
+            
+            pz2 = np.array([[1, 0, 0],
+                        [0, np.cos(-yaw), -np.sin(-yaw)],
+                        [0, np.sin(-yaw),  np.cos(-yaw)]])
+            
+            Z_PI = np.array([[np.cos(np.pi), -np.sin(np.pi), 0],
+                    [np.sin(np.pi), np.cos(np.pi), 0],
+                    [0, 0, 1]])
+            
+            R1_mat = np.matmul(R_mat,pz1)
+            R2_mat = np.matmul(R_mat,pz2)
+
+            sign = check_x_axis_direction(R1_mat)#如果z轴朝上了 将它转180  问题是咋会朝下
+            if sign == 1:
+                pass
+            elif sign == -1:
+                R1_mat = np.matmul(R1_mat, Z_PI)
+                R2_mat = np.matmul(R2_mat, Z_PI)
+
+            q1 = R.from_matrix(R1_mat).as_quat()#应该是RPY转四元数
+            q2 = R.from_matrix(R2_mat).as_quat()
+            q1 = q1.tolist()  # 将NumPy数组转换为列表
+            q2 = q2.tolist()
+            # print("一个点云面的平外缝")
+            # print(q1,q2)
+            result_ping.append(("pw", start_point, end_point, q1, q2))
+            
+            return result_ping,result_shu,result_wai
+        else:
+            ##偏转矩阵 y ##
+            E = np.array([[np.cos(-pitch_of_Verticalweld), 0, np.sin(-pitch_of_Verticalweld)],
+                        [0, 1, 0],
+                        [-np.sin(-pitch_of_Verticalweld), 0, np.cos(-pitch_of_Verticalweld)]])
+
+            R_mat = np.matmul(R_mat,E)
+            
+            q1 = R.from_matrix(R_mat).as_quat()
+            q2 = R.from_matrix(R_mat).as_quat()
+            q1 = q1.tolist()  # 将NumPy数组转换为列表
+            q2 = q2.tolist()
+            # print("即一个点云面的竖外缝")
+            # print(q1,q2)
+            result_wai.append(("sw", start_point, end_point, q1, q2))
+            return result_ping,result_shu,result_wai
+    #不止是有一个面的情况
+    else:
+        # 选择位于平面两侧的点
+        # 随机选取data_shu中的第一个点
+        random_index = np.random.randint(0, data_shu.shape[0])
+        vector1 = data_shu[random_index] - midpoint#得到在某个面上的垂直焊缝的向量
+        vector1 /= np.linalg.norm(vector1)  # 单位化vector1
+
+        # 随机选取下一个点,直到找到与vector1夹角大于10度的向量  也就是在选取的面之外的向量
+        found = False
+        while not found:
+            random_index = np.random.randint(0, data_shu.shape[0])
+            random_point = data_shu[random_index] - midpoint
+            vector2 = random_point / np.linalg.norm(random_point)  # 单位化vector2
+            
+            # 计算两个向量之间的夹角(弧度)
+            dot_product = np.dot(vector1, vector2)
+            angle_rad = np.arccos(dot_product)
+            
+            # 判断角度是否大于10度(转换为弧度)
+            if angle_rad > np.deg2rad(40) and angle_rad < np.deg2rad(140):  #40 到 140度的夹角都加入计算 原本是20 到180
+                found = True
+                # 如果找到了,则保存vector2
+            else:
+                continue
+
+        # 计算并保存最终的fangxiang向量, vector1与vector2均为单位向量
+        vector1_sim_to_z = np.dot(vector1, [0,0,1]) / (np.linalg.norm(vector1))#计算vector1 在 z 轴方向上的投影,也就是 vector1 的 z 分量。
+        vector2_sim_to_z = np.dot(vector2, [0,0,1]) / (np.linalg.norm(vector2))
+        if vector1_sim_to_z > vector2_sim_to_z:
+            vector_shu = vector1
+            vector_ping = vector2
+        else:
+            vector_shu = vector2
+            vector_ping = vector1
+        fangxiang = vector_ping + vector_shu*tan(pitch_of_Horizontalweld)
+        # fangxiang = vector1 + vector2
+        fangxiang /= np.linalg.norm(fangxiang)  # 单位化fangxiang
+
+        #########################################根据vector1和vector2判断内缝外缝#########################################
+        point1 = midpoint + 50 * fangxiang 
+        point2 = midpoint - 50 * fangxiang 
+
+        Rc2w,tc2w = compute_Rc2w_tc2w(file_path_Tw2c)
+        
+        point1_c = np.matmul(Rc2w, point1) + tc2w
+        point2_c = np.matmul(Rc2w, point2) + tc2w
+        a = np.linalg.norm(point1_c)
+        b = np.linalg.norm(point2_c)#求长度    
+
+        if a < b: # 内缝
+            # print("两个点云面的内缝")
+            fangxiang = fangxiang
+        else: # 外缝
+            # print("两个点云面的外缝")
+            fangxiang = -fangxiang
+
+        R_mat, ispingfeng = compute_pose_R(fangxiang, hanfeng, start_point, end_point)
+        if ispingfeng:
+            ##偏转##
+            corner_of_start_point = corner_angle_discrimination(start_point,data,fangxiang)#检查起始是否处于角落
+            corner_of_end_point = corner_angle_discrimination(end_point,data,fangxiang)
+            pi4_pz = atan(1 / (sqrt(2) * tan(np.pi/4)))#CL公式      35.26°
+            yaw_pz =atan(1 / (sqrt(2) * tan(yaw)))#不懂为啥这么变换   反正变换了肯定是比原来角度小?
+            #print(f"yaw:{degrees(yaw)},yaw_pz:{degrees(yaw_pz)}")
+            if corner_of_start_point:
+                q1 = set_yaw_angle(R_mat,pi4_pz)#左右偏转
+                if not corner_of_end_point:
+                    len_hanfeng = np.linalg.norm(hanfeng)
+                    angle = pi4_pz-(pi4_pz)*len_hanfeng/yaw_rate
+                    if angle < -yaw_pz:
+                        angle =-yaw_pz
+                    q2 = set_yaw_angle(R_mat,angle)
+            if corner_of_end_point:
+                q2 = set_yaw_angle(R_mat,-pi4_pz)
+                if not corner_of_start_point:
+                    len_hanfeng = np.linalg.norm(hanfeng)
+                    angle = -pi4_pz+(pi4_pz)*len_hanfeng/yaw_rate
+                    if angle > yaw_pz:
+                        angle = yaw_pz
+                    q1 = set_yaw_angle(R_mat,angle)
+            if not corner_of_start_point and not corner_of_end_point:     
+                q1 = set_yaw_angle(R_mat,yaw_pz)
+                len_hanfeng = np.linalg.norm(hanfeng)
+                angle = yaw_pz-(pi4_pz)*len_hanfeng/yaw_rate
+                if angle < -yaw_pz:
+                    angle =-yaw_pz
+                q2 = set_yaw_angle(R_mat,angle)
+            
+            result_ping.append(("p", start_point, end_point, q1, q2))
+            
+            return result_ping,result_shu,result_wai
+        else:
+            ##偏转##
+            E = np.array([[np.cos(-pitch_of_Verticalweld), 0, np.sin(-pitch_of_Verticalweld)],
+                        [0, 1, 0],
+                        [-np.sin(-pitch_of_Verticalweld), 0, np.cos(-pitch_of_Verticalweld)]])
+
+            R_mat = np.matmul(R_mat,E)
+            
+            q1 = R.from_matrix(R_mat).as_quat()
+            q2 = R.from_matrix(R_mat).as_quat()
+            q1 = q1.tolist()  # 将NumPy数组转换为列表
+            q2 = q2.tolist()
+            # print(q1,q2)
+            result_wai.append(("s", start_point, end_point, q1, q2))
+            return result_ping,result_shu,result_wai        
+
+def run():
+    global yaw,yaw_rate,pitch_of_Horizontalweld,pitch_of_Verticalweld
+    # yaw = np.pi/8
+    yaw = np.pi/2-rospy.get_param("yaw")#内收角(偏航角)
+    pitch_of_Verticalweld = rospy.get_param("pitch_of_Verticalweld")
+    pitch_of_Horizontalweld = rospy.get_param("pitch_of_Horizontalweld")#和底面夹角(俯仰角)
+    yaw_rate = rospy.get_param("yaw_rate")#偏航角过渡速度(角度变化45度/100mm)
+    file_path = rospy.get_param("folder_path")
+    # file_path = ('/home/chen/catkin_ws/data/0603')
+    file_path_pointcloud = os.path.join(file_path, 'pointcloud.txt')
+    file_path_points = os.path.join(file_path, 'points_guihua.txt')
+    file_path_result = os.path.join(file_path, 'result.txt')
+    file_path_Tw2c = os.path.join(file_path, 'Tw2c.txt')
+
+    # 获取数据
+    data = load_point_cloud_from_binary_txt(file_path_pointcloud)#从二进制点云文件获取数据
+    start_points, end_points, midpoints, hanfeng = get_hanfeng(file_path_points)#读points_guihua.txt 并处理得到起点 终点 中点 向量
+
+    # 计算位姿
+    result_ping,result_shu,result_wai = [],[],[]
+    for i in range(len(midpoints)):#遍历所有焊缝
+        result_ping,result_shu,result_wai = get_quaternion(data, midpoints[i], hanfeng[i], start_points[i], end_points[i],result_ping,result_shu,result_wai, file_path_Tw2c)
+        # print(q1," ",q2)
+    result = result_ping + result_shu + result_wai
+
+    # 打开文件准备写入
+    with open(file_path_result, "w") as file:
+        for group in result:
+            # 对于每个数据组,将每个部分用逗号连接,然后在各部分间插入斜杠
+            line = "/".join([",".join(map(str, sublist)) for sublist in group]) + "\n"
+            file.write(line)
+
+    rospy.loginfo("Welding Angle calculation completed")
+if __name__ == '__main__':     
+    
+    run()

+ 5 - 0
catkin_ws/src/lst_robot_r/launch/start.launch

@@ -0,0 +1,5 @@
+<launch>
+  <node pkg="lst_robot_r" name="start" type="start.py" required="true" output="screen">
+  </node>
+
+</launch>

+ 7 - 0
catkin_ws/src/lst_robot_r/msg/JointTrajectoryPoint_ex.msg

@@ -0,0 +1,7 @@
+float64[] positions
+float64[] velocities
+float64[] accelerations
+float64[] effort
+duration time_from_start
+string type
+float64[] sequence

+ 3 - 0
catkin_ws/src/lst_robot_r/msg/JointTrajectory_ex.msg

@@ -0,0 +1,3 @@
+Header header
+string[] joint_names
+JointTrajectoryPoint_ex[] points

+ 70 - 0
catkin_ws/src/lst_robot_r/package.xml

@@ -0,0 +1,70 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>lst_robot_r</name>
+  <version>0.0.0</version>
+  <description>The lst_robot_r package</description>
+
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
+  <!-- Example:  -->
+  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <maintainer email="chen@todo.todo">chen</maintainer>
+
+
+  <!-- One license tag required, multiple allowed, one license per tag -->
+  <!-- Commonly used license strings: -->
+  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
+  <license>TODO</license>
+
+
+  <!-- Url tags are optional, but multiple are allowed, one per tag -->
+  <!-- Optional attribute type can be: website, bugtracker, or repository -->
+  <!-- Example: -->
+  <!-- <url type="website">http://wiki.ros.org/lstrobot_planning</url> -->
+
+
+  <!-- Author tags are optional, multiple are allowed, one per tag -->
+  <!-- Authors do not have to be maintainers, but could be -->
+  <!-- Example: -->
+  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
+
+
+  <!-- The *depend tags are used to specify dependencies -->
+  <!-- Dependencies can be catkin packages or system dependencies -->
+  <!-- Examples: -->
+  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
+  <!--   <depend>roscpp</depend> -->
+  <!--   Note that this is equivalent to the following: -->
+  <!--   <build_depend>roscpp</build_depend> -->
+  <!--   <exec_depend>roscpp</exec_depend> -->
+  <!-- Use build_depend for packages you need at compile time: -->
+  <!--   <build_depend>message_generation</build_depend> -->
+  <!-- Use build_export_depend for packages you need in order to build against this package: -->
+  <!--   <build_export_depend>message_generation</build_export_depend> -->
+  <!-- Use buildtool_depend for build tool packages: -->
+  <!--   <buildtool_depend>catkin</buildtool_depend> -->
+  <!-- Use exec_depend for packages you need at runtime: -->
+  <!--   <exec_depend>message_runtime</exec_depend> -->
+  <!-- Use test_depend for packages you need only for testing: -->
+  <!--   <test_depend>gtest</test_depend> -->
+  <!-- Use doc_depend for packages you need only for building documentation: -->
+  <!--   <doc_depend>doxygen</doc_depend> -->
+  <buildtool_depend>catkin</buildtool_depend>
+  <build_depend>roscpp</build_depend>
+  <build_depend>rospy</build_depend>
+  <build_depend>std_msgs</build_depend>
+  <build_export_depend>roscpp</build_export_depend>
+  <build_export_depend>rospy</build_export_depend>
+  <build_export_depend>std_msgs</build_export_depend>
+  <exec_depend>roscpp</exec_depend>
+  <exec_depend>rospy</exec_depend>
+  <exec_depend>std_msgs</exec_depend>
+  
+ <build_depend>message_generation</build_depend>
+ <exec_depend>message_runtime</exec_depend>
+
+  <!-- The export tag contains other, unspecified, tags -->
+  <export>
+    <!-- Other tools can request additional information be placed here -->
+
+  </export>
+</package>

+ 50 - 0
catkin_ws/src/lst_robot_r/scripts/command.py

@@ -0,0 +1,50 @@
+#! /usr/bin/env python3
+import subprocess
+import rospy
+import os
+
+#file_path = "moveitServer2"
+script_directory = os.path.dirname(os.path.abspath(__file__))
+
+import signal
+
+ 
+def close_rviz(terminal_name):
+    # 使用pgrep查找终端进程
+    pgrep_cmd = "pgrep -f '{}'".format(terminal_name)
+    pids = subprocess.check_output(pgrep_cmd, shell=True).strip().split()
+    
+    # 如果找到了匹配的进程ID,发送SIGTERM信号
+    for pid in pids:
+        try:
+            os.kill(int(pid), signal.SIGTERM)
+        except ProcessLookupError:
+            pass  # 进程可能已经不存在
+
+def load_visual():
+    command = "rosrun visual visual_node"
+    subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
+def load_rviz():
+    command = "roslaunch yunhua_1006a_moveit_config demo.launch"
+    subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
+def launch_publish_pointcloud():
+    file_name = "dycl_0506.py"
+    absolute_path = os.path.join(script_directory, file_name)
+    command = "python3 {}".format(absolute_path)
+    subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
+def launch_moveit_control_server():
+    file_name = "moveitServer2.py"
+    absolute_path = os.path.join(script_directory, file_name)
+    command = "python3 {}".format(absolute_path)
+    subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
+
+def launch_publish_pointcloud_background():
+    file_name = "dycl_0506.py"
+    absolute_path = os.path.join(script_directory, file_name)
+    command = ["python3", absolute_path]
+    subprocess.call(command)
+def launch_moveit_control_server_background():
+    file_name = "moveitServer2.py"
+    absolute_path = os.path.join(script_directory, file_name)
+    command = ["python3", absolute_path]
+    subprocess.call(command)

+ 153 - 0
catkin_ws/src/lst_robot_r/scripts/dycl_0506.py

@@ -0,0 +1,153 @@
+#!/usr/bin/env python3
+import rospy
+import numpy as np
+import open3d as o3d
+from scipy.spatial.transform import Rotation as R
+import os
+from sensor_msgs.msg import PointCloud2
+from sensor_msgs.msg import PointField
+
+
+
+folder_path = rospy.get_param("folder_path")
+file_path = os.path.join(folder_path, 'pointcloud.txt')
+file_path_points = os.path.join(folder_path, 'points.txt')
+#chen############################################################################################
+def cull_pointcloud(data,culling_radius):
+    data_retained,data_culled = [],[]
+    for i in range(data.shape[0]):  # 遍历每一个点 P
+
+        for j in range(len(vectors)):  # 遍历每一个向量 u
+            A = start_points[j] - culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
+            B = end_points[j] + culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
+            aaa = (np.linalg.norm(data[i] - A) + np.linalg.norm(data[i] - B)) <= (2 * culling_radius + np.linalg.norm(B - A))
+            distance = np.linalg.norm(np.cross(vectors[j], data[i]-start_points[j])) / np.linalg.norm(vectors[j])
+
+            # 如果有任何一个距离小于等于10,则标记为不满足条件
+            if distance <= culling_radius and aaa:
+            # if aaa:
+                data_culled.append(data[i])
+                break
+            # 如果该点对所有向量的距离都大于10,则保留该点
+            elif j == len(vectors)-1:
+                data_retained.append(data[i])
+
+    data_retained = np.array(data_retained)
+    data_culled = np.array(data_culled)
+    return data_retained,data_culled    
+
+################################点云降采样################################
+
+# 从文件中读取焊缝起点和终点,并计算两点构成的向量
+def read_and_calculate_vectors(file_path):
+    with open(file_path, 'r') as file:
+        # 逐行读取文件内容
+        lines = file.readlines()
+    start_points,end_points,vectors = [],[],[]
+    for line in lines:
+        # 去除行尾的换行符并按'/'分割每一行
+        points_str = line.strip().split('/')
+        
+        # 确保每一行都正确地分为两部分
+        if len(points_str) == 2:
+            point1_str = points_str[0].split(',')
+            point2_str = points_str[1].split(',')
+            
+            # 转换字符串为浮点数列表,构造三维点
+            point1 = [float(coord) for coord in point1_str]
+            point2 = [float(coord) for coord in point2_str]
+
+            start_points.append(point1)
+            end_points.append(point2)
+            # 计算向量:向量 = 点2 - 点1
+            vector = [p2 - p1 for p1, p2 in zip(point1, point2)]
+            
+            vectors.append(vector)
+    
+    return start_points,end_points,vectors
+
+# 读取文件
+def load_point_cloud_from_binary_txt(file_path):
+    with open(file_path, 'rb') as f:
+        binary_data = f.read()
+
+        # 将二进制数据转换为 NumPy 数组
+        point_cloud = np.frombuffer(binary_data, dtype=np.float64).reshape(-1, 3)
+        # 将数组转换为可写状态
+        point_cloud = np.copy(point_cloud)
+    return point_cloud
+
+
+
+
+pcd = o3d.geometry.PointCloud()
+pcd.points = o3d.utility.Vector3dVector(load_point_cloud_from_binary_txt(file_path))
+pcd = pcd.voxel_down_sample(voxel_size = 3)
+
+################################去掉焊缝周围的点云#################################
+# 计算焊缝向量
+start_points,end_points,vectors = np.array(read_and_calculate_vectors(file_path_points))
+
+data = np.asarray(pcd.points)
+
+
+
+# culling_radius2 = float(15.1)
+# data_retained2,data_culled2 =cull_pointcloud(data,culling_radius2)
+# data_scaled2 = np.array(data_retained2) / 1000
+
+
+data_scaled2 = np.array(data) / 1000
+ptCloud_scaled2 = o3d.geometry.PointCloud()
+ptCloud_scaled2.points = o3d.utility.Vector3dVector(data_scaled2)
+
+#####################################################################################################################################################################
+def build_pointcloud2_msg(points):
+    msg = PointCloud2()
+    msg.header.stamp = rospy.Time(0)
+    msg.header.frame_id = "base_link"
+
+    if len(points.shape) == 3:
+        msg.height = points.shape[1]
+        msg.width = points.shape[0]
+    else:
+        msg.height = 1
+        msg.width = len(points)
+
+    msg.fields = [
+        PointField('x', 0, PointField.FLOAT32, 1),
+        PointField('y', 4, PointField.FLOAT32, 1),
+        PointField('z', 8, PointField.FLOAT32, 1)]
+    msg.is_bigendian = False
+    msg.point_step = 12
+    msg.row_step = msg.point_step * points.shape[0]
+    msg.is_dense = False
+    msg.data = np.asarray(points, np.float32).tobytes()
+    return msg
+
+def talker():
+    pub1 = rospy.Publisher("/pointcloud/output", PointCloud2, queue_size=10)
+    # pub2 = rospy.Publisher("/pointcloud/output2", PointCloud2, queue_size=10)
+    rospy.init_node('publish_pointcloud', anonymous=True)
+    rate = rospy.Rate(10)
+
+    points2 = np.asarray(ptCloud_scaled2.points)
+    # msg1 = build_pointcloud2_msg(points1)
+    msg2 = build_pointcloud2_msg(points2)
+    
+    while not rospy.is_shutdown():
+
+        #机械臂完毕,退出点云发布
+        sign_pointcloud = str(rospy.get_param("sign_pointcloud"))
+        if sign_pointcloud == "1":
+            rospy.set_param("sign_pointcloud",0)
+            break
+
+        pub1.publish(msg2)
+        # pub2.publish(msg2)
+        # print("pointcloud has published,sign_pointcloud ={}".format(sign_pointcloud))
+        rate.sleep()
+
+if __name__ == '__main__':     
+
+    talker()

+ 259 - 0
catkin_ws/src/lst_robot_r/scripts/hjsx.py

@@ -0,0 +1,259 @@
+import numpy as np
+import os
+import rospy
+from math import acos, degrees,tan,atan,sqrt,sin,cos,radians
+from scipy.spatial.transform import Rotation as R
+
+#求向量的模
+def calculate_distance(point1, point2):
+    return np.linalg.norm(np.array(point1) - np.array(point2))
+
+#计算焊缝向量与xy平面夹角 用于判断是平缝还是竖缝
+def calculate_angle_with_xy_plane(point1,point2):
+    # 计算方向向量
+    dir_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], point2[2] - point1[2]])
+    
+    # 计算方向向量在 xy 平面上的投影
+    proj_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], 0])
+    
+    # 计算夹角
+    angle = acos(np.dot(dir_vector, proj_vector) / (np.linalg.norm(dir_vector) * np.linalg.norm(proj_vector)))
+    angle_deg = degrees(angle)
+
+    return angle_deg
+
+
+# 从文件中读取焊缝起点和终点,并分为平缝和竖缝
+def read_hanfeng_from_point_txt(file_path):
+
+    data_ping, data_shu = [],[]
+
+    with open(file_path, 'r') as file:
+        # 逐行读取文件内容
+        lines = file.readlines()
+    flag_sequence = 0
+    for line in lines:
+        # print(line)
+        flag_sequence += 1
+        # 去除行尾的换行符并按'/'分割每一行
+        points_str = line.strip().split('/')
+        
+        point1_str = points_str[0].split(',')
+        point2_str = points_str[1].split(',')
+        
+        # 转换字符串为浮点数列表,构造三维点
+        point1 = [float(coord) for coord in point1_str]
+        point2 = [float(coord) for coord in point2_str]
+
+        angle = calculate_angle_with_xy_plane(point1,point2)
+        
+        if abs(angle) <  rospy.get_param("ping_sta"):#用于判断平缝的角度
+            data_ping.append([point1, point2, flag_sequence])
+        else:
+            data_shu.append([*sorted([point1, point2], key=lambda p: p[2]), flag_sequence]) 
+
+        data = data_ping + data_shu
+
+    return data_ping, data_shu
+
+
+def sort_welds_by_distance_ping(data_ping, reference_point):
+    """根据与参考点的距离对焊缝进行排序"""
+    sorted_data_ping = []#一定放for外
+    for i in range(len(data_ping)):
+        # 计算起点到参考点的距离并排序[[起点与参考点距离,终点与参考点距离,起点坐标,终点坐标,焊缝序号(与points文件中顺序对应)],[],[]....]
+        data_with_distances = [[calculate_distance(start, reference_point),calculate_distance(end, reference_point), start, end,flag_sequence] for start, end,flag_sequence in data_ping]
+        for i in range(len(data_with_distances)):
+            if data_with_distances[i][0] > data_with_distances[i][1]:#若起点比终点离参考点更远 则互换起始点 且将第一个元素变为最近的点(后面用lambda针对第一个元素大小排序)
+                data_with_distances[i][0] = data_with_distances[i][1]
+                tem = data_with_distances[i][2]
+                data_with_distances[i][2] = data_with_distances[i][3]
+                data_with_distances[i][3] = tem
+        data_with_distances.sort(key=lambda x: x[0])#将水平焊缝(起点是离机器人近的那一端)按照起点离参考点的距离排序
+
+        # 初始化结果和当前终点
+        sorted_data_ping.append(data_with_distances.pop(0)[-3:])  # 取出data_with_distances第一个元素的 起点坐标 终点坐标  焊缝序号
+        #reference_point = sorted_data_ping[-1][1] #参考点变更为 sorted_data_ping中的最后一个点   即寻找离当前焊缝终点最近的
+
+        data_ping = [[start, end,flag_sequence] for distances1,distances2, start,end,flag_sequence in data_with_distances]#从弹出已经排好的点的数组重新更新被处理列表
+        
+        #将起始点位置交换回来,保证平缝焊接方向一致   
+        # for i in range(len(sorted_data_ping)):
+        #     sorted_data_ping[i][0], sorted_data_ping[i][1] = sorted_data_ping[i][1], sorted_data_ping[i][0]
+            
+    return sorted_data_ping  #焊接方向最终是由参考点近端向远端焊接  顺序为先找离参考点最近的 然后找其次的
+
+
+# def sort_welds_by_distance_shu(data_shu, reference_point):
+#     """根据与参考点的距离对焊缝进行排序"""
+#     sorted_data_shu = []
+#     for i in range(len(data_shu)):
+#         # 计算起点到参考点的距离并排序
+#         data_with_distances = [[calculate_distance(start, reference_point), start, end ,flag_sequence] for start, end ,flag_sequence in data_shu]
+        
+#         data_with_distances.sort(key=lambda x: x[0])
+
+#         # 初始化结果和当前终点
+#         sorted_data_shu.append(data_with_distances.pop(0)[-3:])
+#         reference_point = sorted_data_shu[-1][1]
+#         data_shu = [[start, end ,flag_sequence] for distances, start,end ,flag_sequence in data_with_distances]
+#     return sorted_data_shu
+
+def compute_pose_R(fangxiang, hanfeng):
+    """wg根据计算出的焊接时z轴负方向的向量(fangxiang)和由起点指向终点的向量(hanfeng)计算旋转矩阵""" #得到的是fangxiang向量相对于基坐标系原点的姿态变换矩阵 多了个绕x转180的变换
+    x, y, z = fangxiang
+
+    # 计算旋转角度
+    rotx = -np.arctan2(y, z)#投影到yz平面的的夹角
+    roty = np.arctan2(x, np.sqrt(y**2 + z**2))#向量和yz面的夹角
+
+    # 构造旋转矩阵 rot x y   先绕x转不影响向量和yz面的夹角?
+    A = np.array([[1, 0, 0],
+                [0, np.cos(rotx), -np.sin(rotx)],
+                [0, np.sin(rotx), np.cos(rotx)]])
+    
+    B = np.array([[np.cos(roty), 0, np.sin(roty)],
+                [0, 1, 0],
+                [-np.sin(roty), 0, np.cos(roty)]])
+    
+    bb = np.matmul(hanfeng, np.matmul(A, B))#先转到XOZ  再转到X  相当于通过将方向向量转到z轴上的方式 让焊缝向量转到XOY平面 通过方向向量和焊缝向量的正交关系求出向量在Z轴上的转角
+    # 区分平缝竖缝
+
+    rotz = np.arctan2(-bb[1], -bb[0])
+      
+    # 构造旋转矩阵 rot z x
+    C = np.array([[np.cos(rotz), -np.sin(rotz), 0],
+                [np.sin(rotz), np.cos(rotz), 0],
+                [0, 0, 1]])
+    D = np.array([[1, 0, 0],
+                    [0, np.cos(np.pi), -np.sin(np.pi)],
+                    [0, np.sin(np.pi), np.cos(np.pi)]])
+
+    ANG_Y=-25
+    E = np.array([[np.cos(radians(ANG_Y)), 0, np.sin(radians(ANG_Y))],
+                [0, 1, 0],
+                [-np.sin(radians(ANG_Y)), 0, np.cos(radians(ANG_Y))]])
+    
+    #A*(B*(C*D))              x*y*z*x(180)
+    #R_mat = np.matmul(A, np.matmul(B, np.matmul(C, D)))
+    #R_mat = np.matmul(A, np.matmul(B, C))
+    R_mat = np.matmul(A, np.matmul(B, np.matmul(C, E)))
+    return R_mat
+
+def run():
+    result=[]
+
+    # 定义参考点,排序
+    #reference_point = (1172.85077147, -1.50259925, 668.30298144)
+    reference_point = (0.0,9000.0, 0.0)
+
+    file_path = rospy.get_param("folder_path")
+    file_path_points = os.path.join(file_path, 'points.txt')
+    file_path_result = os.path.join(file_path, 'result.txt')
+
+    data_ping, data_shu= read_hanfeng_from_point_txt(file_path_points)
+
+
+    # 对焊缝排序
+    sorted_data_ping = sort_welds_by_distance_ping(data_ping, reference_point)
+    # if len(data_ping) > 0:
+    #     a = tuple(sorted_data_ping[-1][1])
+    # else:
+    #     a = reference_point
+    # sorted_welds_shu = sort_welds_by_distance_shu(data_shu, a)
+    sorted_welds = sorted_data_ping# + sorted_welds_shu  #[[起点,终点,序号],[],[]。。。。]
+    
+    #传递焊接顺序(points读入时的编号,从零开始)
+    flag_sequence = [flag_sequence for start,end ,flag_sequence in sorted_welds]
+    rospy.set_param('welding_sequence',flag_sequence)
+
+    sorted_welds_withnoflag = [[start,end]for start,end ,flag_sequence in sorted_welds]
+
+    # with open(file_path_points_guihua, "w") as file:
+    #     for start, end in sorted_welds_withnoflag:
+    #         # 将每一对起点和终点转换为字符串,并用逗号连接,最后以换行符分隔不同的焊缝对
+    #         line = "{},{},{}".format(start[0], start[1], start[2]) + "/" + "{},{},{}".format(end[0], end[1], end[2]) + "\n"
+    #         file.write(line)
+    # rospy.loginfo("Welding sequence calculation completed")
+
+
+
+# 计算位姿 ########################################################################################################
+    if len(sorted_welds_withnoflag)!=2:
+        rospy.loginfo("焊缝数量错误!!!!")
+        #print(len(sorted_welds_withnoflag))
+        # exit(0)
+        return len(sorted_welds_withnoflag)
+    else:
+    
+        point1=sorted_welds_withnoflag[0]
+        point2=sorted_welds_withnoflag[1]
+
+        # middle1=[(point1[0][0]+point1[1][0])/2,(point1[0][1]+point1[1][1])/2,(point1[0][2]+point1[1][2])/2]
+        # middle2=[(point2[0][0]+point2[1][0])/2,(point2[0][1]+point2[1][1])/2,(point2[0][2]+point2[1][2])/2]
+        
+        middle1=[(point1[0][0]+point1[1][0])/2,(point1[0][1]+point1[1][1])/2,0]
+        middle2=[(point2[0][0]+point2[1][0])/2,(point2[0][1]+point2[1][1])/2,0]#不计算z的偏移 就是相对于水平的旋转
+
+        hanfeng1=[point1[1][0]-point1[0][0],point1[1][1]-point1[0][1],point1[1][2]-point1[0][2]]
+        hanfeng2=[point2[1][0]-point2[0][0],point2[1][1]-point2[0][1],point2[1][2]-point2[0][2]]
+        #sorted_welds    #[[起点,终点,序号],[],[]。。。。]
+
+
+        faxiang=[middle2[0]-middle1[0],middle2[1]-middle1[1],middle2[2]-middle1[2]]
+        #shuzhi=np.cross(faxiang,hanfeng1)#向量叉乘 
+        shuzhi=[0,0,1]
+        
+        faxiang/= np.linalg.norm(faxiang)  # 单位化
+        shuzhi /= np.linalg.norm(shuzhi)  # 单位化
+        
+        #ang_md=calculate_angle_with_xy_plane(middle1,middle2)
+
+        # if(point1[0][0]<0 and point2[0][0]<0):
+        #     fangxiang=faxiang+shuzhi*5.6 #arctan(4)=76度
+        # else:
+        #     fangxiang=faxiang-shuzhi*5.6 #arctan(4)=76度
+
+        ang_deg=35
+        fangxiang=-faxiang-shuzhi*tan(radians(90-ang_deg))#arctan(4)=76度
+
+        mat=compute_pose_R(fangxiang,hanfeng1)
+        q = R.from_matrix(mat).as_quat()#应该是RPY转四元数
+        result.append(("s", point1[0],point1[1], q, q))
+
+
+        # if(point1[0][0]<0 and point2[0][0]<0):
+        #     fangxiang=-faxiang+shuzhi*5.6 #arctan(4)=76度
+        # else:
+        #     fangxiang=-faxiang-shuzhi*5.6 #arctan(4)=76度
+
+        fangxiang=faxiang-shuzhi*tan(radians(90-ang_deg)) #arctan(4)=76度
+            
+        mat=compute_pose_R(fangxiang,hanfeng1)
+        q = R.from_matrix(mat).as_quat()#应该是RPY转四元数
+        result.append(("s", point2[0],point2[1], q, q))
+
+
+        # 打开文件准备写入
+        with open(file_path_result, "w") as file:
+            for group in result:
+                # 对于每个数据组,将每个部分用逗号连接,然后在各部分间插入斜杠
+                line = "/".join([",".join(map(str, sublist)) for sublist in group]) + "\n"
+                file.write(line)
+
+
+        rospy.loginfo("顺序与姿态规划完毕 0v0")
+        
+        return len(sorted_welds_withnoflag)
+
+
+if __name__ == '__main__':    
+    run()
+
+
+
+    
+   
+
+
+   

+ 561 - 0
catkin_ws/src/lst_robot_r/scripts/moveitServer2.py

@@ -0,0 +1,561 @@
+# 导入基本ros和moveit库
+import os
+import moveit_msgs.msg
+import rospy, sys
+import moveit_commander      
+import moveit_msgs
+import tf.transformations
+
+from logging.handlers import RotatingFileHandler
+from moveit_commander import MoveGroupCommander, PlanningSceneInterface, RobotCommander
+from moveit_msgs.msg import  PlanningScene, ObjectColor,CollisionObject, AttachedCollisionObject,RobotTrajectory
+from moveit_msgs.msg import RobotState
+from moveit_msgs.msg import Constraints, PositionConstraint, OrientationConstraint
+from shape_msgs.msg import SolidPrimitive
+from sensor_msgs.msg import JointState
+from trajectory_msgs.msg import JointTrajectory,JointTrajectoryPoint
+from geometry_msgs.msg import PoseStamped, Pose,Point,Vector3
+
+from copy import deepcopy
+import numpy as np
+import tf
+from tf.transformations import euler_from_quaternion,quaternion_from_euler,quaternion_from_euler, quaternion_multiply
+import math
+import traceback
+from lst_robot_r.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
+import json
+import termios
+from redis_publisher import Publisher
+from scipy.interpolate import CubicSpline
+
+pi = np.pi
+
+class MoveIt_Control:
+    # 初始化程序
+    def __init__(self, is_use_gripper=False):
+        self.home_pose = []
+        self.hf_num = 0#焊缝计数 从0开始
+        self.hf_fail = []
+        # Init ros configs
+        moveit_commander.roscpp_initialize(sys.argv)
+        self.robot = moveit_commander.RobotCommander()
+        
+        self.arm = moveit_commander.MoveGroupCommander('manipulator')
+        self.arm.set_goal_joint_tolerance(0.0001)
+        self.arm.set_goal_position_tolerance(0.0005)
+        self.arm.set_goal_orientation_tolerance(0.1)
+        #self.arm.set_planner_id("RRTConnet")#不知道能不能用
+
+        self.end_effector_link = self.arm.get_end_effector_link()
+        # 设置机械臂基座的参考系
+        self.reference_frame = 'base_link'
+        self.arm.set_pose_reference_frame(self.reference_frame)
+
+        # # 设置最大规划时间和是否允许重新规划
+        self.arm.set_planning_time(10.0)
+        self.arm.allow_replanning(True)
+
+        self.arm.set_max_acceleration_scaling_factor(1)
+        self.arm.set_max_velocity_scaling_factor(1)
+
+        self.arm.set_num_planning_attempts(10)
+        # 机械臂初始姿态
+        #self.move_j()
+        self.go_home()
+        self.home_pose = self.get_now_pose()
+        #self.go_ready()
+
+    #TODO 使用三次样条插值平滑轨迹
+    def smooth_trajectory(self, trajectory, num_points=0):
+        
+        print(f"原始轨迹点数: {len(trajectory.joint_trajectory.points)}")
+        num_points = len(trajectory.joint_trajectory.points) // 4
+        print(f"当前轨迹点数:{num_points}")
+        # 创建平滑后的轨迹
+        smoothed_trajectory = []
+        for i in range(len(trajectory.joint_trajectory.joint_names)):
+            joint_trajectory = [point.positions[i] for point in trajectory.joint_trajectory.points]
+            cs = CubicSpline(range(len(joint_trajectory)), joint_trajectory)  #创建三次样条插值器
+            smooth_joint_trajectory = cs(np.linspace(0, len(joint_trajectory) - 1, num_points))  #生成平滑后的轨迹
+            smoothed_trajectory.append(smooth_joint_trajectory)
+
+        # 创建平滑后的轨迹点
+        smoothed_trajectory_points = []
+        for j in range(num_points):
+            point = trajectory.joint_trajectory.points[0]
+            smoothed_point = JointTrajectoryPoint()
+            smoothed_point.positions = [smoothed_trajectory[i][j] for i in range(len(smoothed_trajectory))]
+            smoothed_point.time_from_start = rospy.Duration(j * 0.05)  # 控制每个点之间的时间间隔
+            smoothed_trajectory_points.append(smoothed_point)
+
+        # 将平滑后的轨迹生成新的 JointTrajectory
+        trajectory.joint_trajectory.points = smoothed_trajectory_points
+        # print(f"平滑后的轨迹点数: {len(trajectory.joint_trajectory.points)}")
+        
+        return trajectory
+    
+    
+    #TODO plan_cartesian_path
+    def plan_cartesian_path_LLL(self, point_s, point_e, waypoints, trajectory, trajectory_with_type, v=1):
+        fraction = 0.0  # 路径规划覆盖率
+        maxtries = 50  # 最大尝试规划次数
+        attempts = 0  # 已经尝试规划次数
+
+        #起点位置设置为规划组最后一个点
+        start_pose = self.arm.get_current_pose(self.end_effector_link).pose
+        wpose = deepcopy(start_pose)
+        waypoint = []
+        #print(waypoint)
+        if waypoints:
+            wpose.position.x = waypoints[-1].position.x
+            wpose.position.y = waypoints[-1].position.y
+            wpose.position.z = waypoints[-1].position.z
+            wpose.orientation.x = waypoints[-1].orientation.x
+            wpose.orientation.y = waypoints[-1].orientation.y
+            wpose.orientation.z = waypoints[-1].orientation.z
+            wpose.orientation.w = waypoints[-1].orientation.w
+            waypoint.append(deepcopy(wpose))
+
+        #wpose = deepcopy(pose)
+        wpose.position.x = point_s[0]
+        wpose.position.y = point_s[1]
+        wpose.position.z = point_s[2]
+        wpose.orientation.x = point_s[3]
+        wpose.orientation.y = point_s[4]
+        wpose.orientation.z = point_s[5]
+        wpose.orientation.w = point_s[6]
+        waypoint.append(deepcopy(wpose))
+        waypoints.append(deepcopy(wpose))
+
+        wpose.position.x = point_e[0]
+        wpose.position.y = point_e[1]
+        wpose.position.z = point_e[2]
+        wpose.orientation.x = point_e[3]
+        wpose.orientation.y = point_e[4]
+        wpose.orientation.z = point_e[5]
+        wpose.orientation.w = point_e[6]
+        waypoint.append(deepcopy(wpose))
+        waypoints.append(deepcopy(wpose))
+
+        # 尝试规划一条笛卡尔空间下的路径,依次通过所有路点
+        while fraction < 1.0 and attempts < maxtries:
+            (plan, fraction) = self.arm.compute_cartesian_path(
+                waypoint,  # waypoint poses,路点列表
+                0.001,  # eef_step,终端步进值
+                0.0,    # jump_threshold,跳跃阈值
+                True)   # avoid_collisions,避障规划
+            attempts += 1
+
+        if fraction == 1.0 :
+            rospy.loginfo("Path computed successfully.")
+            #traj = plan
+            trajj = plan #取出规划的信息
+            # retimed_planed = self.retime_plan(trajj, v)
+            replan_traj = self.smooth_trajectory(trajj)
+            trajj_with_type = mark_the_traj(trajj, "during-l", welding_sequence)
+            trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"  
+            trajj_with_type.points[-1].type = "end"
+            trajectory.append(trajj)
+            rospy.loginfo("开始执行")
+            moveit_server.arm.execute(replan_traj)
+            rospy.loginfo("执行结束")
+            trajectory_with_type.append(trajj_with_type)
+            err = 0
+        else:
+            err = 1
+            rospy.loginfo("fraction=" + str(fraction) + " failed after " + str(maxtries))   
+            
+        return waypoints, trajectory, trajectory_with_type, err
+    
+    
+    def plan_cartesian_path_point(self, point_ss, point_ee, waypoints, trajectory, trajectory_with_type, v=1):
+        fraction = 0.0  # 路径规划覆盖率
+        maxtries = 50  # 最大尝试规划次数
+        attempts = 0  # 已经尝试规划次数
+
+        #起点位置设置为规划组最后一个点
+        start_pose = self.arm.get_current_pose(self.end_effector_link).pose
+        wpose = deepcopy(start_pose)
+        waypoint = []
+        #print(waypoint)
+        if waypoints:
+            wpose.position.x = waypoints[-1].position.x
+            wpose.position.y = waypoints[-1].position.y
+            wpose.position.z = waypoints[-1].position.z
+            wpose.orientation.x = waypoints[-1].orientation.x
+            wpose.orientation.y = waypoints[-1].orientation.y
+            wpose.orientation.z = waypoints[-1].orientation.z
+            wpose.orientation.w = waypoints[-1].orientation.w
+            waypoint.append(deepcopy(wpose))
+
+        #wpose = deepcopy(pose)
+        wpose.position.x = point_ss[0]
+        wpose.position.y = point_ss[1]
+        wpose.position.z = point_ss[2]
+        wpose.orientation.x = point_ss[3]
+        wpose.orientation.y = point_ss[4]
+        wpose.orientation.z = point_ss[5]
+        wpose.orientation.w = point_ss[6]
+        waypoint.append(deepcopy(wpose))
+        waypoints.append(deepcopy(wpose))
+
+        wpose.position.x = point_ee[0]
+        wpose.position.y = point_ee[1]
+        wpose.position.z = point_ee[2]
+        wpose.orientation.x = point_ee[3]
+        wpose.orientation.y = point_ee[4]
+        wpose.orientation.z = point_ee[5]
+        wpose.orientation.w = point_ee[6]
+        waypoint.append(deepcopy(wpose))
+        waypoints.append(deepcopy(wpose))
+
+        # 尝试规划一条笛卡尔空间下的路径,依次通过所有路点
+        while fraction < 1.0 and attempts < maxtries:
+            (plan, fraction) = self.arm.compute_cartesian_path(
+                waypoint,  # waypoint poses,路点列表
+                0.005,  # eef_step,终端步进值
+                0.0,    # jump_threshold,跳跃阈值
+                True)   # avoid_collisions,避障规划
+            attempts += 1
+
+        if fraction == 1.0 :
+            rospy.loginfo("Path computed successfully.")
+            #traj = plan
+            trajj = plan #取出规划的信息
+            # retimed_planed = self.retime_plan(trajj, v)
+            # replan_traj = self.smooth_trajectory(trajj)
+            trajj_with_type = mark_the_traj(trajj, "during-p", welding_sequence)
+            trajectory.append(trajj)
+            rospy.loginfo("开始执行")
+            moveit_server.arm.execute(trajj)
+            rospy.loginfo("执行结束")
+            trajectory_with_type.append(trajj_with_type)
+            err = 0
+        else:
+            err = 1
+            rospy.loginfo("fraction=" + str(fraction) + " failed after " + str(maxtries))   
+            
+        return waypoints, trajectory, trajectory_with_type, err
+     
+     
+    #TODO retime_plan
+    def retime_plan(self, traj, v):
+        current_state = self.arm.get_current_state()
+        
+        retimed_traj = self.arm.retime_trajectory(
+            current_state,
+            traj,
+            velocity_scaling_factor=0.03,
+            acceleration_scaling_factor=1)
+        
+        return retimed_traj
+    
+    
+    def get_now_pose(self):
+        # 获取机械臂当前位姿
+        current_pose = self.arm.get_current_pose(self.end_effector_link).pose
+        pose = []
+        pose.append(current_pose.position.x)
+        pose.append(current_pose.position.y)
+        pose.append(current_pose.position.z)
+
+        pose.append(current_pose.orientation.x)
+        pose.append(current_pose.orientation.y)
+        pose.append(current_pose.orientation.z)
+        pose.append(current_pose.orientation.w)
+        # 打印位姿信息       
+        #rospy.lohome_poseinfo("Current Pose: {}".format(pose))
+        return pose
+
+
+    def go_home(self, a=1, v=1):
+        rospy.loginfo("go_home start")
+        self.arm.set_max_acceleration_scaling_factor(a)
+        self.arm.set_max_velocity_scaling_factor(v)
+        self.arm.set_named_target('home')
+        rospy.loginfo("get home_point")
+        self.arm.go()
+        rospy.loginfo("go_home end")
+        # rospy.sleep(1)
+        
+
+    def go_home_justplan(self, trajectory, trajectory_with_type, a=1, v=1):
+        rospy.loginfo("go_home start")
+        self.arm.set_max_acceleration_scaling_factor(a)
+        self.arm.set_max_velocity_scaling_factor(v)
+        state = self.arm.get_current_state()
+        if trajectory:
+            state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
+        self.arm.set_start_state(state)
+        self.arm.set_named_target('home')
+        traj = self.arm.plan()
+        trajj = traj[1]
+        moveit_server.arm.execute(trajj)
+        rospy.loginfo("go_home end")
+        traj_with_type = mark_the_traj(trajj, "go-home", welding_sequence)
+        trajectory.append(trajj)
+        trajectory_with_type.append(traj_with_type)
+        return trajectory,trajectory_with_type
+
+
+    #TODO path_planning
+    def path_planning(self, folder_path, gohome=True):
+        file_path_result = os.path.join(folder_path, 'result.txt')
+        all_data = process_welding_data(file_path_result)
+
+        way_points,trajectory,trajectory_with_type = [], [], []
+        for i in range(len(all_data)):
+            rospy.loginfo("共读取到%d条焊缝,开始规划第%d条", len(all_data), i+1)
+            start_point = all_data[i][0]
+            end_point = all_data[i][1]
+            q1 = all_data[i][2]
+            q2 = all_data[i][3]
+
+            point11 = [start_point[0]/1000, start_point[1]/1000, start_point[2]/1000, q1[0], q1[1], q1[2], q1[3]]
+            point22 = [end_point[0]/1000, end_point[1]/1000, end_point[2]/1000, q2[0], q2[1], q2[2], q2[3]]
+            
+            up_value = -0.08
+            point_up = [point11[0], point11[1], point11[2]-up_value, point11[3], point11[4], point11[5], point11[6]]
+            # 点到点规划
+            way_points, trajectory, trajectory_with_type, error = self.plan_cartesian_path_point(point_up, point11, way_points, trajectory, trajectory_with_type, v=speed_v)
+            rospy.loginfo("末端执行器上移完毕")
+            rospy.loginfo("*******************")
+            
+            if(error == 1):
+                rospy.loginfo("焊缝规划出现失败 清空路径列表")
+                rospy.loginfo("*******************")
+                trajectory.clear()
+                trajectory_with_type.clear()
+                break
+            
+            # 焊缝规划
+            way_points, trajectory, trajectory_with_type, error = self.plan_cartesian_path_LLL(point11, point22, way_points, trajectory, trajectory_with_type, v=speed_v)
+            
+            rospy.loginfo("第%d条焊缝规划完毕", i+1)
+            rospy.loginfo("*******************")
+            if(error == 1):
+                rospy.loginfo("焊缝规划出现失败 清空路径列表")
+                rospy.loginfo("*******************")
+                trajectory.clear()
+                trajectory_with_type.clear()
+                break
+            #向上移动末端执行器
+            if i<len(all_data):
+                up_value = -0.08
+                point_up = [point22[0], point22[1], point22[2]-up_value, point22[3], point22[4], point22[5], point22[6]]
+                # 点到点规划
+                way_points, trajectory, trajectory_with_type, error = self.plan_cartesian_path_point(point22, point_up, way_points,trajectory,trajectory_with_type,v=speed_v)
+                rospy.loginfo("末端执行器上移完毕")
+                rospy.loginfo("*******************")
+            
+            if(error == 1):
+                rospy.loginfo("焊缝规划出现失败 清空路径列表")
+                rospy.loginfo("*******************")
+                trajectory.clear()
+                trajectory_with_type.clear()
+                break
+        #rospy.loginfo("All of The trajectory Plan successfully")
+        #rospy.loginfo("*******************")
+        if gohome:
+            #trajectory,trajectory_with_type= self.move_p_flexible(trajectory,trajectory_with_type)
+            trajectory, trajectory_with_type = self.go_home_justplan(trajectory, trajectory_with_type)
+
+        traj_merge = merge_trajectories(trajectory)
+        trajectory_with_type_merge = merge_trajectories_with_type(trajectory_with_type)
+        return trajectory, traj_merge, trajectory_with_type_merge
+
+###########################################################class end#############################################################
+def process_welding_data(filename):
+    all_data = []  # 用来存储每一行处理后的数据
+    with open(filename, 'r') as file:
+        for line in file:
+            parts = line.strip().split('/')
+            coordinates_and_poses = [part.split(',') for part in parts[1:]]
+            
+            start_point = tuple(map(float, coordinates_and_poses[0][:3]))  # 使用元组以避免修改
+            end_point = tuple(map(float, coordinates_and_poses[1][:3]))
+            q1 = tuple(map(float, coordinates_and_poses[2][:4]))
+            q2 = tuple(map(float, coordinates_and_poses[3][:4]))
+            
+            # 收集每行处理后的数据
+            all_data.append((start_point, end_point, q1, q2))
+
+    return all_data
+
+# 焊缝全部轨迹点
+def mark_the_traj(traj,TYPE,SEQUENCE):
+    traj_with_type = JointTrajectory_ex()
+    traj_with_type.header = traj.joint_trajectory.header
+    traj_with_type.joint_names = traj.joint_trajectory.joint_names
+    traj_with_type.points = [
+        JointTrajectoryPoint_ex(
+            positions = point.positions,
+            velocities = point.velocities,
+            accelerations = point.accelerations,
+            effort = point.effort,
+            type = TYPE,
+            sequence = SEQUENCE
+        ) for point in traj.joint_trajectory.points
+    ]
+    return traj_with_type
+
+
+def merge_trajectories(trajectories):
+    if not trajectories:
+        return None
+    
+    # 创建一个新的 JointTrajectory 对象
+    merged_trajectory = JointTrajectory()
+    merged_trajectory.header = trajectories[0].joint_trajectory.header
+    merged_trajectory.joint_names = trajectories[0].joint_trajectory.joint_names
+    
+    # 初始化时间累加器
+    last_time_from_start = rospy.Duration(0)
+    
+    # 合并所有 trajectories 的 points
+    for traj in trajectories:
+
+        for point in traj.joint_trajectory.points:
+            # 创建新的轨迹点
+            new_point = deepcopy(point)
+            # 累加时间
+            new_point.time_from_start += last_time_from_start
+            merged_trajectory.points.append(new_point)
+        
+        # 更新时间累加器为当前轨迹的最后一个点的时间
+        if traj.joint_trajectory.points:
+            last_time_from_start = traj.joint_trajectory.points[-1].time_from_start + last_time_from_start
+    
+    return merged_trajectory
+
+
+def merge_trajectories_with_type(trajectory_with_type):
+    if not trajectory_with_type:
+        return None
+    
+    # 创建一个新的 JointTrajectory 对象
+    merged_trajectory_with_type = JointTrajectory_ex()
+    merged_trajectory_with_type.header = trajectory_with_type[0].header
+    merged_trajectory_with_type.joint_names = trajectory_with_type[0].joint_names
+    
+    # 初始化时间累加器
+    last_time_from_start = rospy.Duration(0)
+    
+    # 合并所有 trajectories 的 points
+    for traj in trajectory_with_type:
+
+        for point in traj.points:
+            # 创建新的轨迹点
+            new_point = deepcopy(point)
+            # 累加时间
+            new_point.time_from_start += last_time_from_start
+            merged_trajectory_with_type.points.append(new_point)
+        
+        # 更新时间累加器为当前轨迹的最后一个点的时间
+        if traj.points:
+            last_time_from_start = traj.points[-1].time_from_start + last_time_from_start
+    
+    return merged_trajectory_with_type
+
+
+class py_msgs():
+    fial = []
+    shun_xv = []
+    class point():
+        xyz_list = []
+        type = []
+
+
+#redis消息格式
+def ROS2PY_msgs(msgs, m_sr):
+    for i in range(len(msgs.points)):
+
+        if msgs.points[i].type == "during-p" or msgs.points[i].type =="start" or msgs.points[i].type =="end":
+            py_msgs.point.xyz_list.append(msgs.points[i].positions)
+            py_msgs.point.type.append(msgs.points[i].type)
+    py_msgs.fail = m_sr.hf_fail.copy()
+    py_msgs.shun_xv = msgs.points[0].sequence.copy()
+
+    # 打印规划信息
+    print("关节轨迹点信息:")
+    for i in range(len(py_msgs.point.type)):
+        print(py_msgs.point.xyz_list[i])
+        print(py_msgs.point.type[i])
+
+    message = {
+        'positions': py_msgs.point.xyz_list,  # 规划路径点结果
+        'flags': py_msgs.point.type,    # 规划路径点的类型,焊接点移动点
+        'weld_order': py_msgs.shun_xv,  # 规划路径顺序
+        'failed': py_msgs.fail,  # 规划路径失败的焊缝
+    }
+    return json.dumps(message)
+    # for i in range(len(py_msgs.point.type)):
+    #     moveit_server.move_j(py_msgs.point.xyz_list[i])
+    #     #input("任意键继续")
+
+# def get_valid_input(factor, default):
+#     while True:
+#         user_input=input(factor)
+#         if user_input=="":
+#             return default
+#         try:
+#             value=float(user_input)
+#             if 0<value<=1:
+#                 return value
+#             else:
+#                 rospy.logerr("缩放因子必须在(0, 1]范围内,请重新输入!")
+#         except ValueError:
+#             rospy.logerr("输入值无效,请根据提示重新输入!")
+
+# def get_user_input():
+#     """获取用户输入的速度和加速度缩放因子,并在控制台中打印信息和错误提示"""
+#     DEFUALT_V = 1.0
+#     DEFUALT_A = 1.0
+     
+#     try:
+#         termios.tcflush(sys.stdin, termios.TCIFLUSH)   #清空输入缓存
+#         rospy.loginfo("输入缓存区已清空!")
+        
+#         vv=get_valid_input("请输入速度缩放因子(0-1, 默认为1): ", DEFUALT_V)
+#         #a=get_valid_input("请输入加速度缩放因子(0-1, 默认为1): ", DEFUALT_A)
+          
+#         #rospy.loginfo(f"用户输入的速度缩放因子为{vv}")
+#         return vv
+#     except Exception as e:
+#         rospy.logerr(f"发生错误:{e}")
+   
+# def ROS2_msgs_write(msgs, m_sr):
+#     for i in range(len(msgs.points)):
+#         py_msgs.point.xyz_list.append(msgs.points[i].positions)
+    
+#     f_p = os.path.join(folder_path, 'outtt.txt')
+#     with open(f_p,'w') as file:
+#         for point in py_msgs.point.xyz_list:
+#             file.write(' '.join(str(value) for value in point)+ "\n") 
+        
+
+if __name__ =="__main__":
+    publisher = Publisher()
+
+    folder_path = rospy.get_param("folder_path")
+    rospy.init_node('moveit_control_server', anonymous=False)   
+    moveit_server = MoveIt_Control(is_use_gripper=False)  
+    welding_sequence = rospy.get_param('welding_sequence')
+
+    speed_v = 0.001
+    # speed_v=get_user_input()
+    # rospy.loginfo(f"用户输入的速度缩放因子为{speed_v}")
+
+    trajectory, trajectory_merge, trajectory_with_type_merge = moveit_server.path_planning(folder_path)
+
+    #moveit_server.go_ready()       #合并后的轨迹也需要从ready点开始执行
+
+    
+    # rospy.loginfo("开始执行合并后轨迹")
+    # moveit_server.arm.execute(trajectory_merge)
+    # #ROS2_msgs_write(trajectory_with_type_merge,moveit_server)
+    # rospy.loginfo("合并后轨迹执行完毕")
+    
+    message = ROS2PY_msgs(trajectory_with_type_merge, moveit_server)
+    publisher.pub_plan_result(message)
+    print("路径规划信息已发布....")

+ 45 - 0
catkin_ws/src/lst_robot_r/scripts/redis_publisher.py

@@ -0,0 +1,45 @@
+import time
+import redis
+
+def redis_init(max_retries=5, retry_delay=1):
+    pool = redis.ConnectionPool(host='192.168.100.133', port=6379, db=0)    #ip地址和端口号
+    retries = 0
+    while retries < max_retries:
+        try:
+            rds = redis.Redis(connection_pool=pool)
+            if rds.ping():
+                print("Connected to Redis successfully.")
+                return rds
+            else:
+                print("Redis 连接失败,正在尝试重新连接...")
+        except redis.ConnectionError as e:
+            print(f"Connection error (retry {retries + 1} of {max_retries}): {e}")
+        except Exception as e:
+            print(f"An error occurred (retry {retries + 1} of {max_retries}): {e}")
+
+        # 增加延迟时间,防止过于频繁的重试
+        time.sleep(retry_delay * (1 ** retries))
+        retries += 1
+
+    print("多次尝试重连失败,检查redis服务是否开启.")
+    return None
+
+class Publisher:
+    def __init__(self):
+        self.rds = redis_init()
+        if self.rds is None:
+            raise Exception("Redis 初始化失败")
+
+    def pub_plan_result(self, result_dict):
+        """
+        发布路径规划结果
+        """
+        if self.rds is not None:
+            self.rds.publish('ros_plan_result', result_dict)
+        else:
+            self.redis_init()
+            self.rds.publish('ros_plan_result', result_dict)
+
+if __name__ == '__main__':
+    Publisher()
+

+ 126 - 0
catkin_ws/src/lst_robot_r/scripts/start.py

@@ -0,0 +1,126 @@
+#! /usr/bin/env python3
+import sys
+import rospy
+import os
+import command
+import subprocess
+import hjsx
+import threading
+import numpy as np
+import multiprocessing
+import actionlib_msgs.msg._GoalStatusArray
+from moveit_msgs.msg import PlanningScene
+from dynamic_reconfigure.client import Client
+from rospy.exceptions import ROSException
+from std_srvs.srv import Empty
+from rospy.service import ServiceException
+from redis_publisher import Publisher
+
+
+def wait_for_topic(topic_name, message_type):
+    try:
+        message = rospy.wait_for_message(topic_name, message_type, timeout=None)
+        return message
+    except rospy.ROSException as e:
+        rospy.logerr(f"等待话题 {topic_name} 时程序被中断: {e}")
+        return None
+    
+def clear_octomap():
+    try:
+        clear_octomap_service = rospy.ServiceProxy('/clear_octomap', Empty)  # 创建服务代理
+        clear_octomap_service()  # 尝试调用服务
+        rospy.loginfo("Octomap has been cleared.")
+    except ServiceException as e:
+        rospy.loginfo("Failed to call /clear_octomap service or it is not available. Skipping operation.")
+
+waited_once = False
+tim_list = []
+
+if __name__ == "__main__":
+    command.load_rviz()
+    rospy.init_node("start_node")
+
+    # 初始化各种类型参数
+    rospy.set_param("ping_sta", 45)#用于判断平缝的角度
+    # rospy.set_param("sign_control",1)
+    rospy.set_param("sign_pointcloud", 0)
+    rospy.set_param("folder_path", "/root/catkin_ws/data")
+
+
+    rospy.loginfo("等待rviz启动")
+    wait_for_topic("/execute_trajectory/status", actionlib_msgs.msg.GoalStatusArray)
+    
+    publisher = Publisher()
+    publisher.rds.set('sign_control', 0)
+    
+    while not rospy.is_shutdown():
+        # sign_control = str(rospy.get_param("sign_control"))
+        sign_control = publisher.rds.get('sign_control').decode('ascii')
+        
+        if sign_control == "0":
+            if not waited_once:
+                print("等待点云数据准备完成...")
+                waited_once = True
+                
+        elif sign_control == "1":
+            # publisher.rds.set('sign_control', 0)
+            
+            # 清除场景   点云计算并发布
+            clear_octomap()
+            process = multiprocessing.Process(target=command.launch_publish_pointcloud_background)
+            process.start()
+
+            # #计算焊接顺序和焊接姿态
+            # hjsx.run()
+            
+            # 等待 /move_group/monitored_planning_scene 话题发布消息
+            rospy.loginfo("等待场景地图加载完毕...")
+            wait_for_topic('/move_group/monitored_planning_scene', PlanningScene)
+            rospy.loginfo(f"场景地图已加载完毕")
+            rospy.set_param("sign_pointcloud", 1)
+
+            flag = hjsx.run()
+            # print(flag)
+            if flag == 2:
+                publisher.rds.set('sign_control', 0)    
+                command.load_visual()
+
+                #rospy.loginfo("运行moveitserver2.py")
+                process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
+                process.start()
+
+                # while rospy.get_param("sign_control"):
+                #     pass
+                waited_once = False
+            else:
+                publisher.rds.set('sign_control', 0)
+                waited_once = False
+
+
+ 
+        elif sign_control == "2":
+            # publisher.rds.set('sign_control', 0)
+            
+            flag = hjsx.run()
+            if flag == 2:
+                publisher.rds.set('sign_control', 0)
+                command.load_visual()
+
+                process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
+                process.start()
+
+            # while rospy.get_param("sign_control"):
+            #     pass
+                waited_once = False
+                
+            else:
+                publisher.rds.set('sign_control', 0)
+                waited_once = False
+            
+        # elif sign_control == "3":
+        #     rospy.loginfo("正在关闭规划器....")
+        #     command.close_rviz("/usr/bin/python3 /opt/ros/noetic/bin/roslaunch yunhua_1006a_moveit_config demo.launch")
+        #     sys.exit(0)
+
+    
+    

+ 49 - 0
catkin_ws/src/visual/CMakeLists.txt

@@ -0,0 +1,49 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(visual)
+
+find_package(catkin REQUIRED COMPONENTS
+  roscpp
+  rospy
+  std_msgs
+  yunhua_1006a_moveit_config
+)
+
+catkin_package(
+
+)
+
+include_directories(
+# include
+  ${catkin_INCLUDE_DIRS}
+)
+
+
+find_package(catkin REQUIRED
+  COMPONENTS
+    interactive_markers
+    moveit_core
+    moveit_visual_tools
+    moveit_ros_planning
+    moveit_ros_planning_interface
+    moveit_ros_perception
+    pluginlib
+    geometric_shapes
+    pcl_ros
+    pcl_conversions
+    rosbag
+    tf2_ros
+    tf2_eigen
+    tf2_geometry_msgs
+)
+
+find_package(Eigen3 REQUIRED)
+find_package(Boost REQUIRED system filesystem date_time thread)
+
+include_directories(${THIS_PACKAGE_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS})
+
+add_executable(visual_node src/visual_tools.cpp)
+target_link_libraries(visual_node ${catkin_LIBRARIES} )#${Boost_LIBRARIES})
+
+install(TARGETS visual_node DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
+
+install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

+ 68 - 0
catkin_ws/src/visual/package.xml

@@ -0,0 +1,68 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>visual</name>
+  <version>0.0.0</version>
+  <description>The visual package</description>
+
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
+  <!-- Example:  -->
+  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <maintainer email="robot@todo.todo">robot</maintainer>
+
+
+  <!-- One license tag required, multiple allowed, one license per tag -->
+  <!-- Commonly used license strings: -->
+  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
+  <license>TODO</license>
+
+
+  <!-- Url tags are optional, but multiple are allowed, one per tag -->
+  <!-- Optional attribute type can be: website, bugtracker, or repository -->
+  <!-- Example: -->
+  <!-- <url type="website">http://wiki.ros.org/visual</url> -->
+
+
+  <!-- Author tags are optional, multiple are allowed, one per tag -->
+  <!-- Authors do not have to be maintainers, but could be -->
+  <!-- Example: -->
+  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
+
+
+  <!-- The *depend tags are used to specify dependencies -->
+  <!-- Dependencies can be catkin packages or system dependencies -->
+  <!-- Examples: -->
+  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
+  <!--   <depend>roscpp</depend> -->
+  <!--   Note that this is equivalent to the following: -->
+  <!--   <build_depend>roscpp</build_depend> -->
+  <!--   <exec_depend>roscpp</exec_depend> -->
+  <!-- Use build_depend for packages you need at compile time: -->
+  <!--   <build_depend>message_generation</build_depend> -->
+  <!-- Use build_export_depend for packages you need in order to build against this package: -->
+  <!--   <build_export_depend>message_generation</build_export_depend> -->
+  <!-- Use buildtool_depend for build tool packages: -->
+  <!--   <buildtool_depend>catkin</buildtool_depend> -->
+  <!-- Use exec_depend for packages you need at runtime: -->
+  <!--   <exec_depend>message_runtime</exec_depend> -->
+  <!-- Use test_depend for packages you need only for testing: -->
+  <!--   <test_depend>gtest</test_depend> -->
+  <!-- Use doc_depend for packages you need only for building documentation: -->
+  <!--   <doc_depend>doxygen</doc_depend> -->
+  <buildtool_depend>catkin</buildtool_depend>
+  <build_depend>roscpp</build_depend>
+  <build_depend>rospy</build_depend>
+  <build_depend>std_msgs</build_depend>
+  <build_export_depend>roscpp</build_export_depend>
+  <build_export_depend>rospy</build_export_depend>
+  <build_export_depend>std_msgs</build_export_depend>
+  <exec_depend>roscpp</exec_depend>
+  <exec_depend>rospy</exec_depend>
+  <exec_depend>std_msgs</exec_depend>
+
+
+  <!-- The export tag contains other, unspecified, tags -->
+  <export>
+    <!-- Other tools can request additional information be placed here -->
+
+  </export>
+</package>

+ 251 - 0
catkin_ws/src/visual/src/visual_tools.cpp

@@ -0,0 +1,251 @@
+
+#include <moveit_msgs/DisplayRobotState.h>
+#include <moveit_msgs/DisplayTrajectory.h>
+
+#include <moveit_msgs/AttachedCollisionObject.h>
+#include <moveit_msgs/CollisionObject.h>
+
+#include <moveit_visual_tools/moveit_visual_tools.h>
+
+#include <iostream>
+#include <fstream>
+#include <string>
+#include <vector>
+
+using namespace std; 
+#define pi 3.1415926
+
+void euler2quat(float phi, float theta, float psi, float quat[4]) {
+    float c1 = cos(phi / 2);
+    float c2 = cos(theta / 2);
+    float c3 = cos(psi / 2);
+    float s1 = sin(phi / 2);
+    float s2 = sin(theta / 2);
+    float s3 = sin(psi / 2);
+    quat[0] = c1*c2*c3 + s1*s2*s3;
+    quat[1] = s1*c2*c3 - c1*s2*s3;
+    quat[2] = c1*s2*c3 + s1*c2*s3;
+    quat[3] = c1*c2*s3 - s1*s2*c3;
+}
+
+ 
+int read_points() {
+    std::ifstream file("points.txt"); // 打开文件
+    if (!file.is_open()) {
+        std::cerr << "无法打开文件" << std::endl;
+        return 1;
+    }
+  
+    std::string line;
+    while (getline(file, line)) { // 逐行读取文件内容
+        std::cout << line << std::endl; // 打印到控制台
+    }
+ 
+    file.close(); // 关闭文件
+    return 0;
+}
+
+//@brief: 指定单个或多个分隔符(单个字符)分割字符串
+//@param: src 原字符串;delimiter 单个或多个分隔符(单个字符)
+vector<string> splitStr(const string& src, const string& delimiter) {
+	std::vector<string> vtStr;
+
+	// 入参检查
+	// 1.原字符串为空返回空 vector
+	if (src == "") {
+		return vtStr;
+	}
+	// 2.分隔符为空返回单个元素为原字符串的 vector
+	if (delimiter == "") {
+		vtStr.push_back(src);
+		return vtStr;
+	}
+
+	string::size_type startPos = 0;
+	auto index = src.find_first_of(delimiter);
+	while (index != string::npos) {
+		auto str = src.substr(startPos, index - startPos);
+		if (str != "") {
+			vtStr.push_back(str);
+		}
+		startPos = index + 1;
+		index = src.find_first_of(delimiter, startPos);
+	}
+	// 取最后一个子串
+	auto str = src.substr(startPos);
+	if (str != "") {
+		vtStr.push_back(str);
+	}
+
+	return vtStr;
+}
+
+int main(int argc, char** argv)
+{
+  float res[4]={0};
+  ros::init(argc, argv, "visual_node");//初始化节点
+  //ros::NodeHandle node_handle;//“大管家”句柄
+  ros::AsyncSpinner spinner(1);//ROS多线程订阅消息,这里开了一个线程???
+  spinner.start();//启动线程
+
+  namespace rvt = rviz_visual_tools;//导入rviz_visual_tools这个namespace,同时使用别名rvt
+  moveit_visual_tools::MoveItVisualTools visual_tools("base_link");//创建MoveItVisualTools对象
+
+  visual_tools.deleteAllMarkers();//清除旧的标记(markers)
+  visual_tools.loadRemoteControl();//加载Remote control 主要功能是激活RVIZ里面的“按钮GUI”,操作人员可以通过GUI按钮/键盘来控制程序运行下一步
+  Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity();//将text_pose初始化为单位阵,再做其他操作。虽然称为3D,实质上为4*4矩阵。
+  text_pose.translation().z() = 1.75;//设置坐标
+  
+  geometry_msgs::Pose target_pose1;///创建一个四元数的位姿
+  geometry_msgs::Pose target_pose2;///创建一个四元数的位姿
+  std::vector<geometry_msgs::Pose> waypoints[20];//定义焊接的路径点列表(创建一个 vector 容器)
+ 
+  //euler2quat(pi,180*pi/180.0,0,res);//ryp角转四元数 设定好姿态
+  // target_pose1.orientation.x=res[0];
+  // target_pose1.orientation.y=res[1];
+  // target_pose1.orientation.z=res[2];
+  // target_pose1.orientation.w = res[3];
+
+  std::string f_path;
+  std::string line;
+  std::vector<string> l;
+
+  ros::param::get("folder_path", f_path);
+  f_path=f_path+"/result.txt";
+  std::ifstream file(f_path); // 打开文件
+  int num=0;
+  if (file.is_open()) 
+  {
+    while (getline(file, line)) 
+    {       
+      l=splitStr(line,"sp,/");
+      target_pose1.position.x = std::stod(l[0])/1000;
+      target_pose1.position.y = std::stod(l[1])/1000;
+      target_pose1.position.z = std::stod(l[2])/1000;
+
+      target_pose2.position.x = std::stod(l[3])/1000;
+      target_pose2.position.y = std::stod(l[4])/1000;
+      target_pose2.position.z = std::stod(l[5])/1000;
+
+      target_pose1.orientation.x= std::stod(l[6]);
+      target_pose1.orientation.y= std::stod(l[7]);
+      target_pose1.orientation.z= std::stod(l[8]);
+      target_pose1.orientation.w = std::stod(l[9]);
+
+      target_pose2.orientation.x= std::stod(l[10]);
+      target_pose2.orientation.y= std::stod(l[11]);
+      target_pose2.orientation.z= std::stod(l[12]);
+      target_pose2.orientation.w = std::stod(l[13]);
+
+      waypoints[num].push_back(target_pose1);//添加到路径点列表
+      waypoints[num].push_back(target_pose2);//添加到路径点列表
+      num++;
+
+      // for (int i=0 ;i<l.size();i++) 
+      // {
+        
+		  //   std::cout << l[i]<< " ";
+	    // }
+      // std::cout<<std::endl;
+
+    }
+
+  }
+  file.close(); // 关闭文件
+  
+  // double xxx,yyy,zzz,xxx2,yyy2,zzz2,xxx3,yyy3,zzz3;
+  // double qx,qy,qz,qw;
+  // ros::param::get("xxx", xxx);
+  // ros::param::get("yyy", yyy);
+  // ros::param::get("zzz", zzz);
+
+  // ros::param::get("qx", qx);
+  // ros::param::get("qy", qy);
+  // ros::param::get("qz", qz);
+  // ros::param::get("qw", qw);
+
+  // target_pose2.position.x = xxx/1000;
+  // target_pose2.position.y = yyy/1000;
+  // target_pose2.position.z = zzz/1000;
+  // target_pose2.orientation.x= qx;
+  // target_pose2.orientation.y= qy;
+  // target_pose2.orientation.z= qz;
+  // target_pose2.orientation.w = qw;
+  // waypoints[num].push_back(target_pose2);//添加到路径点列表
+  // num++;
+
+  // ros::param::get("xxx2", xxx2);
+  // ros::param::get("yyy2", yyy2);
+  // ros::param::get("zzz2", zzz2);
+  // target_pose2.position.x = xxx2/1000;
+  // target_pose2.position.y = yyy2/1000;
+  // target_pose2.position.z = zzz2/1000;
+  // waypoints[num].push_back(target_pose2);//添加到路径点列表
+  // num++;
+
+  // ros::param::get("xxx3", xxx3);
+  // ros::param::get("yyy3", yyy3);
+  // ros::param::get("zzz3", zzz3);
+  // target_pose2.position.x = xxx3/1000;
+  // target_pose2.position.y = yyy3/1000;
+  // target_pose2.position.z = zzz3/1000;
+  // waypoints[num].push_back(target_pose2);//添加到路径点列表
+  // num++;
+
+
+  visual_tools.deleteAllMarkers();//清除所有标记
+  visual_tools.publishText(text_pose, "robot", rvt::WHITE, rvt::XLARGE);//文本标记
+  for(int k=0;k<num;k++)
+  {
+    visual_tools.publishPath(waypoints[k], rvt::PINK , rvt::XXXSMALL);//路径?
+    for (std::size_t i = 0; i < waypoints[k].size(); ++i)
+      visual_tools.publishAxisLabeled(waypoints[k][i], "point" + std::to_string (k)+ "  "+std::to_string(waypoints[k][i].position.x)+ "  "+ std::to_string(waypoints[k][i].position.y)+ "  "+ std::to_string(waypoints[k][i].position.z), rvt::XXXSMALL);//坐标系
+    visual_tools.trigger();
+  }
+  // while (ros::ok())
+  // {
+    
+  // }
+  
+  
+  ros::shutdown();
+  return 0;
+}
+
+/*
+BLACK 	
+BROWN 	
+BLUE 	
+CYAN 	
+GREY 	
+DARK_GREY 	
+GREEN 	
+LIME_GREEN 	
+MAGENTA 	
+ORANGE 	
+PURPLE 	
+RED 	
+PINK 	
+WHITE 	
+YELLOW 	
+TRANSLUCENT 	
+TRANSLUCENT_LIGHT 	
+TRANSLUCENT_DARK 	
+RAND 	
+CLEAR 	
+DEFAULT 
+
+XXXXSMALL 	
+XXXSMALL 	
+XXSMALL 	
+XSMALL 	
+SMALL 	
+MEDIUM 	
+LARGE 	
+XLARGE 	
+XXLARGE 	
+XXXLARGE 	
+XXXXLARGE 	
+REGULAR 
+
+*/

+ 11 - 0
catkin_ws/src/yunhua_1006a_moveit_config/.setup_assistant

@@ -0,0 +1,11 @@
+moveit_setup_assistant_config:
+  URDF:
+    package: yunhua_ryhj
+    relative_path: urdf/yunhua_ryhj.urdf
+    xacro_args: ""
+  SRDF:
+    relative_path: config/yunhua_ryhj.srdf
+  CONFIG:
+    author_name: 123
+    author_email: 123@163.com
+    generated_timestamp: 1736132785

+ 10 - 0
catkin_ws/src/yunhua_1006a_moveit_config/CMakeLists.txt

@@ -0,0 +1,10 @@
+cmake_minimum_required(VERSION 3.1.3)
+project(yunhua_1006a_moveit_config)
+
+find_package(catkin REQUIRED)
+
+catkin_package()
+
+install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+  PATTERN "setup_assistant.launch" EXCLUDE)
+install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

+ 5 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/cartesian_limits.yaml

@@ -0,0 +1,5 @@
+cartesian_limits:
+  max_trans_vel: 1
+  max_trans_acc: 2.25
+  max_trans_dec: -5
+  max_rot_vel: 1.57

+ 18 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/chomp_planning.yaml

@@ -0,0 +1,18 @@
+planning_time_limit: 10.0
+max_iterations: 200
+max_iterations_after_collision_free: 5
+smoothness_cost_weight: 0.1
+obstacle_cost_weight: 1.0
+learning_rate: 0.01
+smoothness_cost_velocity: 0.0
+smoothness_cost_acceleration: 1.0
+smoothness_cost_jerk: 0.0
+ridge_factor: 0.0
+use_pseudo_inverse: false
+pseudo_inverse_ridge_factor: 1e-4
+joint_update_limit: 0.1
+collision_clearance: 0.2
+collision_threshold: 0.07
+use_stochastic_descent: true
+enable_failure_recovery: false
+max_recovery_attempts: 5

+ 13 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/fake_controllers.yaml

@@ -0,0 +1,13 @@
+controller_list:
+  - name: fake_manipulator_controller
+    type: $(arg fake_execution_type)
+    joints:
+      - joint1
+      - joint2
+      - joint3
+      - joint4
+      - joint5
+      - joint6
+initial:  # Define initial robot poses per group
+  - group: manipulator
+    pose: home

+ 4 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/gazebo_controllers.yaml

@@ -0,0 +1,4 @@
+# Publish joint_states
+joint_state_controller:
+  type: joint_state_controller/JointStateController
+  publish_rate: 50

+ 292 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/gazebo_yunhua_ryhj.urdf

@@ -0,0 +1,292 @@
+<?xml version="1.0" encoding="utf-8" ?>
+<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
+     Commit Version: 1.6.0-4-g7f85cfe  Build Version: 1.6.7995.38578
+     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
+<robot name="yunhua_ryhj">
+    <link name="base_link">
+        <inertial>
+            <origin xyz="-0.073946 -7.5783E-05 0.079686" rpy="0 0 0" />
+            <mass value="26.825" />
+            <inertia ixx="0.29447" ixy="-0.00068906" ixz="-0.0018702" iyy="0.70624" iyz="8.3009E-05" izz="0.88713" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/base_link.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="0.1451 0.1451 0.1451 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/base_link.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <link name="link1">
+        <inertial>
+            <origin xyz="0.040145 -0.0017665 -0.17281" rpy="0 0 0" />
+            <mass value="39.487" />
+            <inertia ixx="0.98418" ixy="-0.16112" ixz="-0.47642" iyy="1.5184" iyz="-0.10144" izz="1.2525" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link1.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 1 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link1.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint1" type="revolute">
+        <origin xyz="0 0 0.511" rpy="0 0 0" />
+        <parent link="base_link" />
+        <child link="link1" />
+        <axis xyz="0 0 1" />
+        <limit lower="-2.617995" upper="2.617995" effort="0" velocity="2.827" />
+    </joint>
+    <link name="link2">
+        <inertial>
+            <origin xyz="-0.030086 0.33235 0.14338" rpy="0 0 0" />
+            <mass value="11.602" />
+            <inertia ixx="0.54948" ixy="0.0072392" ixz="0.0022966" iyy="0.040699" iyz="-0.0016648" izz="0.56667" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link2.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 0 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link2.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint2" type="revolute">
+        <origin xyz="0.225 0 0" rpy="1.5708 0 0" />
+        <parent link="link1" />
+        <child link="link2" />
+        <axis xyz="0 0 -1" />
+        <limit lower="-1.448624" upper="1.570797" effort="0" velocity="2.827" />
+    </joint>
+    <link name="link3">
+        <inertial>
+            <origin xyz="0.080981 0.12571 -9.0574E-05" rpy="0 0 0" />
+            <mass value="13.961" />
+            <inertia ixx="0.19012" ixy="-0.11007" ixz="0.0065658" iyy="0.19149" iyz="0.011087" izz="0.28951" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link3.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 1 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link3.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint3" type="revolute">
+        <origin xyz="0 0.76 0" rpy="0 0 0" />
+        <parent link="link2" />
+        <child link="link3" />
+        <axis xyz="0 0 -1" />
+        <limit lower="-1.308998" upper="1.186824" effort="0" velocity="3.463" />
+    </joint>
+    <link name="link4">
+        <inertial>
+            <origin xyz="-0.0016575 0.026244 0.35186" rpy="0 0 0" />
+            <mass value="10.585" />
+            <inertia ixx="0.16278" ixy="0.00030377" ixz="0.0018777" iyy="0.18729" iyz="-0.010668" izz="0.051504" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link4.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 0 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link4.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint4" type="revolute">
+        <origin xyz="0.9915 0.215 0" rpy="0 -1.5708 0" />
+        <parent link="link3" />
+        <child link="link4" />
+        <axis xyz="0 0 -1" />
+        <limit lower="-2.356196" upper="2.356196" effort="0" velocity="7.106" />
+    </joint>
+    <link name="link5">
+        <inertial>
+            <origin xyz="-5.2388E-05 -0.061382 -0.0003515" rpy="0 0 0" />
+            <mass value="1.0093" />
+            <inertia ixx="0.0042625" ixy="6.072E-07" ixz="-2.4533E-07" iyy="0.0023268" iyz="-0.00020667" izz="0.0032649" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link5.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 0 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link5.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint5" type="revolute">
+        <origin xyz="0 0 0" rpy="-1.5708 3.1416 -1.5708" />
+        <parent link="link4" />
+        <child link="link5" />
+        <axis xyz="0 0 -1" />
+        <limit lower="-1.570797" upper="2.268929" effort="0" velocity="5.639" />
+    </joint>
+    <link name="link6">
+        <inertial>
+            <origin xyz="-0.073417 -0.00013522 0.2336" rpy="0 0 0" />
+            <mass value="0.62764" />
+            <inertia ixx="0.0028394" ixy="1.5554E-06" ixz="0.00027709" iyy="0.0011602" iyz="-4.9029E-08" izz="0.0030715" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link6.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="0.75294 0.75294 0.75294 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://yunhua_ryhj/meshes/link6.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint6" type="revolute">
+        <origin xyz="0 0 0" rpy="1.5708 0 0" />
+        <parent link="link5" />
+        <child link="link6" />
+        <axis xyz="0 0 1" />
+        <limit lower="-3.839726" upper="3.839726" effort="0" velocity="0" />
+    </joint>
+    <link name="link_flp">
+        <collision>
+            <geometry>
+                <box size="0.0001 0.0001 0.0001" />
+            </geometry>
+            <origin rpy="0 0 0" xyz="0 0 0" />
+        </collision>
+        <inertial>
+            <mass value="0.1" />
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <inertia ixx="0.03" iyy="0.03" izz="0.03" ixy="0.0" ixz="0.0" iyz="0.0" />
+        </inertial>
+    </link>
+    <joint name="joint_flp" type="fixed">
+        <parent link="link6" />
+        <child link="link_flp" />
+        <origin rpy="0 0 3.1415926" xyz="0 0 0.140" />
+    </joint>
+    <link name="link_end" />
+    <joint name="joint_end" type="fixed">
+        <parent link="link_flp" />
+        <child link="link_end" />
+        <origin rpy="0.0 0.736255 0.0" xyz="0.085387  0.007948  0.525332" />
+    </joint>
+    <transmission name="trans_joint1">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint1">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint1_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint2">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint2">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint2_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint3">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint3">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint3_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint4">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint4">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint4_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint5">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint5">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint5_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint6">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint6">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint6_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <gazebo>
+        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
+            <robotNamespace>/</robotNamespace>
+        </plugin>
+    </gazebo>
+</robot>
+

+ 40 - 0
catkin_ws/src/yunhua_1006a_moveit_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: 2.827
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint2:
+    has_velocity_limits: true
+    max_velocity: 2.827
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint3:
+    has_velocity_limits: true
+    max_velocity: 3.463
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint4:
+    has_velocity_limits: true
+    max_velocity: 7.106
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint5:
+    has_velocity_limits: true
+    max_velocity: 5.639
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint6:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0

+ 7 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/kinematics.yaml

@@ -0,0 +1,7 @@
+manipulator:
+  kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
+  kinematics_solver_search_resolution: 0.005
+  kinematics_solver_timeout: 0.005
+  goal_joint_tolerance: 0.0001
+  goal_position_tolerance: 0.0001
+  goal_orientation_tolerance: 0.001

+ 198 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/ompl_planning.yaml

@@ -0,0 +1,198 @@
+planner_configs:
+  AnytimePathShortening:
+    type: geometric::AnytimePathShortening
+    shortcut: true  # Attempt to shortcut all new solution paths
+    hybridize: true  # Compute hybrid solution trajectories
+    max_hybrid_paths: 24  # Number of hybrid paths generated per iteration
+    num_planners: 4  # The number of default planners to use for planning
+    planners: ""  # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
+  SBL:
+    type: geometric::SBL
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+  EST:
+    type: geometric::EST
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05
+  LBKPIECE:
+    type: geometric::LBKPIECE
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9
+    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5
+  BKPIECE:
+    type: geometric::BKPIECE
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9
+    failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5
+    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5
+  KPIECE:
+    type: geometric::KPIECE
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05
+    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9 (0.0,1.]
+    failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5
+    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5
+  RRT:
+    type: geometric::RRT
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05
+  RRTConnect:
+    type: geometric::RRTConnect
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+  RRTstar:
+    type: geometric::RRTstar
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05
+    delay_collision_checking: 1  # Stop collision checking as soon as C-free parent found. default 1
+  TRRT:
+    type: geometric::TRRT
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05
+    max_states_failed: 10  # when to start increasing temp. default: 10
+    temp_change_factor: 2.0  # how much to increase or decrease temp. default: 2.0
+    min_temperature: 10e-10  # lower limit of temp change. default: 10e-10
+    init_temperature: 10e-6  # initial temperature. default: 10e-6
+    frontier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+    frontier_node_ratio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+    k_constant: 0.0  # value used to normalize expresssion. default: 0.0 set in setup()
+  PRM:
+    type: geometric::PRM
+    max_nearest_neighbors: 10  # use k nearest neighbors. default: 10
+  PRMstar:
+    type: geometric::PRMstar
+  FMT:
+    type: geometric::FMT
+    num_samples: 1000  # number of states that the planner should sample. default: 1000
+    radius_multiplier: 1.1  # multiplier used for the nearest neighbors search radius. default: 1.1
+    nearest_k: 1  # use Knearest strategy. default: 1
+    cache_cc: 1  # use collision checking cache. default: 1
+    heuristics: 0  # activate cost to go heuristics. default: 0
+    extended_fmt: 1  # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+  BFMT:
+    type: geometric::BFMT
+    num_samples: 1000  # number of states that the planner should sample. default: 1000
+    radius_multiplier: 1.0  # multiplier used for the nearest neighbors search radius. default: 1.0
+    nearest_k: 1  # use the Knearest strategy. default: 1
+    balanced: 0  # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
+    optimality: 1  # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
+    heuristics: 1  # activates cost to go heuristics. default: 1
+    cache_cc: 1  # use the collision checking cache. default: 1
+    extended_fmt: 1  # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+  PDST:
+    type: geometric::PDST
+  STRIDE:
+    type: geometric::STRIDE
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05
+    use_projected_distance: 0  # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
+    degree: 16  # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
+    max_degree: 18  # max degree of a node in the GNAT. default: 12
+    min_degree: 12  # min degree of a node in the GNAT. default: 12
+    max_pts_per_leaf: 6  # max points per leaf in the GNAT. default: 6
+    estimated_dimension: 0.0  # estimated dimension of the free space. default: 0.0
+    min_valid_path_fraction: 0.2  # Accept partially valid moves above fraction. default: 0.2
+  BiTRRT:
+    type: geometric::BiTRRT
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    temp_change_factor: 0.1  # how much to increase or decrease temp. default: 0.1
+    init_temperature: 100  # initial temperature. default: 100
+    frontier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+    frontier_node_ratio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+    cost_threshold: 1e300  # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
+  LBTRRT:
+    type: geometric::LBTRRT
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05
+    epsilon: 0.4  # optimality approximation factor. default: 0.4
+  BiEST:
+    type: geometric::BiEST
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+  ProjEST:
+    type: geometric::ProjEST
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05
+  LazyPRM:
+    type: geometric::LazyPRM
+    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+  LazyPRMstar:
+    type: geometric::LazyPRMstar
+  SPARS:
+    type: geometric::SPARS
+    stretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+    sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
+    dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001
+    max_failures: 1000  # maximum consecutive failure limit. default: 1000
+  SPARStwo:
+    type: geometric::SPARStwo
+    stretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+    sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
+    dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001
+    max_failures: 5000  # maximum consecutive failure limit. default: 5000
+  AITstar:
+    type: geometric::AITstar
+    use_k_nearest: 1  # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+    rewire_factor: 1.001  # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+    samples_per_batch: 100  # batch size. Valid values: [1:1:1000]. Default: 100
+    use_graph_pruning: 1  # enable graph pruning (1) or not (0). Default: 1
+    find_approximate_solutions: 0  # track approximate solutions (1) or not (0). Default: 0
+    set_max_num_goals: 1  # maximum number of goals sampled from sampleable goal regions. Valid values: [1:1:1000]. Default: 1
+  ABITstar:
+    type: geometric::ABITstar
+    use_k_nearest: 1  # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+    rewire_factor: 1.001  # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+    samples_per_batch: 100  # batch size. Valid values: [1:1:1000]. Default: 100
+    use_graph_pruning: 1  # enable graph pruning (1) or not (0). Default: 1
+    prune_threshold_as_fractional_cost_change: 0.1  # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
+    delay_rewiring_to_first_solution: 0  # delay (1) or not (0) rewiring until a solution is found. Default: 0
+    use_just_in_time_sampling: 0  # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
+    drop_unconnected_samples_on_prune: 0  # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
+    stop_on_each_solution_improvement: 0  # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
+    use_strict_queue_ordering: 0  # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
+    find_approximate_solutions: 0  # track approximate solutions (1) or not (0). Default: 0
+    initial_inflation_factor: 1000000  # inflation factor for the initial search. Valid values: [1.0:0.01:1000000.0]. Default: 1000000
+    inflation_scaling_parameter: 10  # scaling parameter for the inflation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
+    truncation_scaling_parameter: 5.0  # scaling parameter for the truncation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
+  BITstar:
+    type: geometric::BITstar
+    use_k_nearest: 1  # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+    rewire_factor: 1.001  # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+    samples_per_batch: 100  # batch size. Valid values: [1:1:1000]. Default: 100
+    use_graph_pruning: 1  # enable graph pruning (1) or not (0). Default: 1
+    prune_threshold_as_fractional_cost_change: 0.1  # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
+    delay_rewiring_to_first_solution: 0  # delay (1) or not (0) rewiring until a solution is found. Default: 0
+    use_just_in_time_sampling: 0  # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
+    drop_unconnected_samples_on_prune: 0  # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
+    stop_on_each_solution_improvement: 0  # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
+    use_strict_queue_ordering: 0  # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
+    find_approximate_solutions: 0  # track approximate solutions (1) or not (0). Default: 0
+manipulator:
+  default_planner_config: RRTConnect
+  planner_configs:
+    - AnytimePathShortening
+    - SBL
+    - EST
+    - LBKPIECE
+    - BKPIECE
+    - KPIECE
+    - RRT
+    - RRTConnect
+    - RRTstar
+    - TRRT
+    - PRM
+    - PRMstar
+    - FMT
+    - BFMT
+    - PDST
+    - STRIDE
+    - BiTRRT
+    - LBTRRT
+    - BiEST
+    - ProjEST
+    - LazyPRM
+    - LazyPRMstar
+    - SPARS
+    - SPARStwo
+    - AITstar
+    - ABITstar
+    - BITstar
+  projection_evaluator: joints(joint1,joint2)
+  longest_valid_segment_fraction: 0.005

+ 0 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/ros_controllers.yaml


+ 9 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/sensors_3d.yaml

@@ -0,0 +1,9 @@
+sensors:
+  - filtered_cloud_topic: filtered_cloud
+    max_range: 5.0
+    max_update_rate: 1.0
+    padding_offset: 0.1
+    padding_scale: 1.0
+    point_cloud_topic: /pointcloud/output
+    point_subsample: 1
+    sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater

+ 2 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/simple_moveit_controllers.yaml

@@ -0,0 +1,2 @@
+controller_list:
+  []

+ 39 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/stomp_planning.yaml

@@ -0,0 +1,39 @@
+stomp/manipulator:
+  group_name: manipulator
+  optimization:
+    num_timesteps: 60
+    num_iterations: 40
+    num_iterations_after_valid: 0
+    num_rollouts: 30
+    max_rollouts: 30
+    initialization_method: 1  # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+    control_cost_weight: 0.0
+  task:
+    noise_generator:
+      - class: stomp_moveit/NormalDistributionSampling
+        stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
+    cost_functions:
+      - class: stomp_moveit/CollisionCheck
+        collision_penalty: 1.0
+        cost_weight: 1.0
+        kernel_window_percentage: 0.2
+        longest_valid_joint_move: 0.05
+    noisy_filters:
+      - class: stomp_moveit/JointLimits
+        lock_start: True
+        lock_goal: True
+      - class: stomp_moveit/MultiTrajectoryVisualization
+        line_width: 0.02
+        rgb: [255, 255, 0]
+        marker_array_topic: stomp_trajectories
+        marker_namespace: noisy
+    update_filters:
+      - class: stomp_moveit/PolynomialSmoother
+        poly_order: 6
+      - class: stomp_moveit/TrajectoryVisualization
+        line_width: 0.05
+        rgb: [0, 191, 255]
+        error_rgb: [255, 0, 0]
+        publish_intermediate: True
+        marker_topic: stomp_trajectory
+        marker_namespace: optimized

+ 57 - 0
catkin_ws/src/yunhua_1006a_moveit_config/config/yunhua_ryhj.srdf

@@ -0,0 +1,57 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<!--This does not replace URDF, and is not an extension of URDF.
+    This is a format for representing semantic information about the robot structure.
+    A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
+-->
+<robot name="yunhua_ryhj">
+    <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
+    <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
+    <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
+    <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
+    <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
+    <group name="manipulator">
+        <chain base_link="base_link" tip_link="link_end"/>
+    </group>
+    <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
+    <group_state name="zero" group="manipulator">
+        <joint name="joint1" value="0"/>
+        <joint name="joint2" value="0"/>
+        <joint name="joint3" value="0"/>
+        <joint name="joint4" value="0"/>
+        <joint name="joint5" value="0"/>
+        <joint name="joint6" value="0"/>
+    </group_state>
+    <group_state name="home" group="manipulator">
+        <joint name="joint1" value="0"/>
+        <joint name="joint2" value="0"/>
+        <joint name="joint3" value="0"/>
+        <joint name="joint4" value="0"/>
+        <joint name="joint5" value="1.57"/>
+        <joint name="joint6" value="0"/>
+    </group_state>
+    <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
+    <disable_collisions link1="base_link" link2="link1" reason="Adjacent"/>
+    <disable_collisions link1="base_link" link2="link2" reason="Never"/>
+    <disable_collisions link1="base_link" link2="link3" reason="Never"/>
+    <disable_collisions link1="base_link" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link1" link2="link2" reason="Adjacent"/>
+    <disable_collisions link1="link1" link2="link3" reason="Never"/>
+    <disable_collisions link1="link1" link2="link4" reason="Never"/>
+    <disable_collisions link1="link1" link2="link5" reason="Never"/>
+    <disable_collisions link1="link1" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link2" link2="link3" reason="Adjacent"/>
+    <disable_collisions link1="link2" link2="link4" reason="Never"/>
+    <disable_collisions link1="link2" link2="link5" reason="Never"/>
+    <disable_collisions link1="link2" link2="link6" reason="Never"/>
+    <disable_collisions link1="link2" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link3" link2="link4" reason="Adjacent"/>
+    <disable_collisions link1="link3" link2="link5" reason="Never"/>
+    <disable_collisions link1="link3" link2="link6" reason="Never"/>
+    <disable_collisions link1="link3" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link4" link2="link5" reason="Adjacent"/>
+    <disable_collisions link1="link4" link2="link6" reason="Never"/>
+    <disable_collisions link1="link4" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link5" link2="link6" reason="Adjacent"/>
+    <disable_collisions link1="link5" link2="link_flp" reason="Never"/>
+    <disable_collisions link1="link6" link2="link_flp" reason="Adjacent"/>
+</robot>

+ 21 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/chomp_planning_pipeline.launch.xml

@@ -0,0 +1,21 @@
+<launch>
+  <arg name="start_state_max_bounds_error" default="0.1" />
+  <arg name="jiggle_fraction" default="0.05" />
+  <!-- The request adapters (plugins) used when planning. ORDER MATTERS! -->
+  <arg name="planning_adapters"
+       default="default_planner_request_adapters/LimitMaxCartesianLinkSpeed
+                default_planner_request_adapters/AddTimeParameterization
+                default_planner_request_adapters/ResolveConstraintFrames
+                default_planner_request_adapters/FixWorkspaceBounds
+                default_planner_request_adapters/FixStartStateBounds
+                default_planner_request_adapters/FixStartStateCollision
+                default_planner_request_adapters/FixStartStatePathConstraints"
+                />
+
+  <param name="planning_plugin" value="chomp_interface/CHOMPPlanner" />
+  <param name="request_adapters" value="$(arg planning_adapters)" />
+  <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
+  <param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
+
+  <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/chomp_planning.yaml" />
+</launch>

+ 15 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/default_warehouse_db.launch

@@ -0,0 +1,15 @@
+<launch>
+
+  <arg name="reset" default="false"/>
+  <!-- If not specified, we'll use a default database location -->
+  <arg name="moveit_warehouse_database_path" default="$(find yunhua_1006a_moveit_config)/default_warehouse_mongo_db" />
+
+  <!-- Launch the warehouse with the configured database location -->
+  <include file="$(dirname)/warehouse.launch">
+    <arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" />
+  </include>
+
+  <!-- If we want to reset the database, run this node -->
+  <node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />
+
+</launch>

+ 66 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/demo.launch

@@ -0,0 +1,66 @@
+<launch>
+
+  <!-- specify the planning pipeline -->
+  <arg name="pipeline" default="ompl" />
+
+  <!-- By default, we do not start a database (it can be large) -->
+  <arg name="db" default="false" />
+  <!-- Allow user to specify database location -->
+  <arg name="db_path" default="$(find yunhua_1006a_moveit_config)/default_warehouse_mongo_db" />
+
+  <!-- By default, we are not in debug mode -->
+  <arg name="debug" default="false" />
+
+  <!-- By default, we will load or override the robot_description -->
+  <arg name="load_robot_description" default="true"/>
+
+  <!-- Choose controller manager: fake, simple, or ros_control -->
+  <arg name="moveit_controller_manager" default="fake" />
+  <!-- Set execution mode for fake execution controllers -->
+  <arg name="fake_execution_type" default="interpolate" />
+
+  <!-- By default, hide joint_state_publisher's GUI in 'fake' controller_manager mode -->
+  <arg name="use_gui" default="false" />
+  <arg name="use_rviz" default="true" />
+
+  <!-- If needed, broadcast static tf for robot root -->
+
+  <group if="$(eval arg('moveit_controller_manager') == 'fake')">
+    <!-- We do not have a real robot connected, so publish fake joint states via a joint_state_publisher
+         MoveIt's fake controller's joint states are considered via the 'source_list' parameter -->
+    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" unless="$(arg use_gui)">
+      <rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam>
+    </node>
+    <!-- If desired, a GUI version is available allowing to move the simulated robot around manually
+         This corresponds to moving around the real robot without the use of MoveIt. -->
+    <node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" if="$(arg use_gui)">
+      <rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam>
+    </node>
+
+    <!-- Given the published joint states, publish tf for the robot links -->
+    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
+  </group>
+
+  <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
+  <include file="$(dirname)/move_group.launch">
+    <arg name="allow_trajectory_execution" value="true"/>
+    <arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" />
+    <arg name="fake_execution_type" value="$(arg fake_execution_type)"/>
+    <arg name="info" value="true"/>
+    <arg name="debug" value="$(arg debug)"/>
+    <arg name="pipeline" value="$(arg pipeline)"/>
+    <arg name="load_robot_description" value="$(arg load_robot_description)"/>
+  </include>
+
+  <!-- Run Rviz and load the default config to see the state of the move_group node -->
+  <include file="$(dirname)/moveit_rviz.launch" if="$(arg use_rviz)">
+    <arg name="rviz_config" value="$(dirname)/moveit.rviz"/>
+    <arg name="debug" value="$(arg debug)"/>
+  </include>
+
+  <!-- If database loading was enabled, start mongodb as well -->
+  <include file="$(dirname)/default_warehouse_db.launch" if="$(arg db)">
+    <arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
+  </include>
+
+</launch>

+ 21 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/demo_gazebo.launch

@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<launch>
+  <!-- MoveIt options -->
+  <arg name="pipeline" default="ompl" doc="Planning pipeline to use with MoveIt"/>
+
+  <!-- Gazebo options -->
+  <arg name="gazebo_gui" default="true" doc="Start Gazebo GUI"/>
+  <arg name="paused" default="false" doc="Start Gazebo paused"/>
+  <arg name="world_name" default="worlds/empty.world" doc="Gazebo world file"/>
+  <arg name="world_pose" default="-x 0 -y 0 -z 0 -R 0 -P 0 -Y 0" doc="Pose to spawn the robot at"/>
+
+  <!-- Launch Gazebo and spawn the robot -->
+  <include file="$(dirname)/gazebo.launch" pass_all_args="true"/>
+
+  <!-- Launch MoveIt -->
+  <include file="$(dirname)/demo.launch" pass_all_args="true">
+    <!-- robot_description is loaded by gazebo.launch, to enable Gazebo features -->
+    <arg name="load_robot_description" value="false" />
+    <arg name="moveit_controller_manager" value="ros_control" />
+  </include>
+</launch>

+ 12 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/fake_moveit_controller_manager.launch.xml

@@ -0,0 +1,12 @@
+<launch>
+
+  <!-- execute the trajectory in 'interpolate' mode or jump to goal position in 'last point' mode -->
+  <arg name="fake_execution_type" default="interpolate" />
+
+  <!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
+  <param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/>
+
+  <!-- The rest of the params are specific to this plugin -->
+  <rosparam subst_value="true" file="$(find yunhua_1006a_moveit_config)/config/fake_controllers.yaml"/>
+
+</launch>

+ 34 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/gazebo.launch

@@ -0,0 +1,34 @@
+<?xml version="1.0"?>
+<launch>
+  <!-- Gazebo options -->
+  <arg name="gazebo_gui" default="true" doc="Start Gazebo GUI"/>
+  <arg name="paused" default="false" doc="Start Gazebo paused"/>
+  <arg name="world_name" default="worlds/empty.world" doc="Gazebo world file"/>
+  <arg name="world_pose" default="-x 0 -y 0 -z 0 -R 0 -P 0 -Y 0" doc="Pose to spawn the robot at"/>
+  <arg name="initial_joint_positions" default=" -J joint1 0 -J joint2 0 -J joint3 0 -J joint4 0 -J joint5 0 -J joint6 0" doc="Initial joint configuration of the robot"/>
+
+  <!-- Start Gazebo paused to allow the controllers to pickup the initial pose -->
+  <include file="$(find gazebo_ros)/launch/empty_world.launch" pass_all_args="true">
+    <arg name="paused" value="true"/>
+  </include>
+
+  <!-- Set the robot urdf on the parameter server -->
+  <param name="robot_description" textfile="$(find yunhua_1006a_moveit_config)/config/gazebo_yunhua_ryhj.urdf" />
+
+  <!-- Unpause the simulation after loading the robot model -->
+  <arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
+
+  <!-- Spawn the robot in Gazebo -->
+  <node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot $(arg unpause) $(arg world_pose) $(arg initial_joint_positions)"
+    respawn="false" output="screen" />
+
+  <!-- Load the controller parameters onto the parameter server -->
+  <rosparam file="$(find yunhua_1006a_moveit_config)/config/gazebo_controllers.yaml" />
+  <include file="$(dirname)/ros_controllers.launch"/>
+
+  <!-- Spawn the Gazebo ROS controllers -->
+  <node name="gazebo_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_state_controller" />
+
+  <!-- Given the published joint states, publish tf for the robot links -->
+  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
+</launch>

+ 17 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/joystick_control.launch

@@ -0,0 +1,17 @@
+<launch>
+  <!-- See moveit_ros/visualization/doc/joystick.rst for documentation -->
+
+  <arg name="dev" default="/dev/input/js0" />
+
+  <!-- Launch joy node -->
+  <node pkg="joy" type="joy_node" name="joy">
+    <param name="dev" value="$(arg dev)" /> <!-- Customize this to match the location your joystick is plugged in on-->
+    <param name="deadzone" value="0.2" />
+    <param name="autorepeat_rate" value="40" />
+    <param name="coalesce_interval" value="0.025" />
+  </node>
+
+  <!-- Launch python interface -->
+  <node pkg="moveit_ros_visualization" type="moveit_joy.py" output="screen" name="moveit_joy"/>
+
+</launch>

+ 105 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/move_group.launch

@@ -0,0 +1,105 @@
+<launch>
+
+  <!-- GDB Debug Option -->
+  <arg name="debug" default="false" />
+  <arg unless="$(arg debug)" name="launch_prefix" value="" />
+  <arg     if="$(arg debug)" name="launch_prefix"
+           value="gdb -x $(dirname)/gdb_settings.gdb --ex run --args" />
+
+  <!-- Verbose Mode Option -->
+  <arg name="info" default="$(arg debug)" />
+  <arg unless="$(arg info)" name="command_args" value="" />
+  <arg     if="$(arg info)" name="command_args" value="--debug" />
+
+  <!-- move_group settings -->
+  <arg name="pipeline" default="ompl" />
+  <arg name="allow_trajectory_execution" default="true"/>
+  <arg name="moveit_controller_manager" default="simple" />
+  <arg name="fake_execution_type" default="interpolate"/>
+  <arg name="max_safe_path_cost" default="1"/>
+  <arg name="publish_monitored_planning_scene" default="true"/>
+
+  <arg name="capabilities" default=""/>
+  <arg name="disable_capabilities" default=""/>
+  <!-- load these non-default MoveGroup capabilities (space seperated) -->
+  <!--
+  <arg name="capabilities" value="
+                a_package/AwsomeMotionPlanningCapability
+                another_package/GraspPlanningPipeline
+                " />
+  -->
+
+  <!-- inhibit these default MoveGroup capabilities (space seperated) -->
+  <!--
+  <arg name="disable_capabilities" value="
+                move_group/MoveGroupKinematicsService
+                move_group/ClearOctomapService
+                " />
+  -->
+
+  <arg name="load_robot_description" default="false" />
+  <!-- load URDF, SRDF and joint_limits configuration -->
+  <include file="$(dirname)/planning_context.launch">
+    <arg name="load_robot_description" value="$(arg load_robot_description)" />
+  </include>
+
+  <!-- Planning Pipelines -->
+  <group ns="move_group/planning_pipelines">
+
+    <!-- OMPL -->
+    <include file="$(dirname)/planning_pipeline.launch.xml">
+      <arg name="pipeline" value="ompl" />
+    </include>
+
+    <!-- CHOMP -->
+    <include file="$(dirname)/planning_pipeline.launch.xml">
+      <arg name="pipeline" value="chomp" />
+    </include>
+
+    <!-- Pilz Industrial Motion -->
+    <include file="$(dirname)/planning_pipeline.launch.xml">
+      <arg name="pipeline" value="pilz_industrial_motion_planner" />
+    </include>
+
+    <!-- Support custom planning pipeline -->
+    <include if="$(eval arg('pipeline') not in ['ompl', 'chomp', 'pilz_industrial_motion_planner'])"
+             file="$(dirname)/planning_pipeline.launch.xml">
+      <arg name="pipeline" value="$(arg pipeline)" />
+    </include>
+  </group>
+
+  <!-- Trajectory Execution Functionality -->
+  <include ns="move_group" file="$(dirname)/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
+    <arg name="moveit_manage_controllers" value="true" />
+    <arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" />
+    <arg name="fake_execution_type" value="$(arg fake_execution_type)" />
+  </include>
+
+  <!-- Sensors Functionality -->
+  <include ns="move_group" file="$(dirname)/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
+    <arg name="moveit_sensor_manager" value="yunhua_ryhj" />
+  </include>
+
+  <!-- Start the actual move_group node/action server -->
+  <node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
+    <!-- Set the display variable, in case OpenGL code is used internally -->
+    <env name="DISPLAY" value="$(optenv DISPLAY :0)" />
+
+    <param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
+    <param name="sense_for_plan/max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
+    <param name="default_planning_pipeline" value="$(arg pipeline)" />
+    <param name="capabilities" value="$(arg capabilities)" />
+    <param name="disable_capabilities" value="$(arg disable_capabilities)" />
+
+    <!-- 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 -->
+    <param name="monitor_dynamics" value="false" />
+
+    <!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
+    <param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
+    <param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
+    <param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
+    <param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
+  </node>
+
+</launch>

+ 378 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/moveit.rviz

@@ -0,0 +1,378 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 84
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /TF1/Frames1
+      Splitter Ratio: 0.5
+    Tree Height: 814
+  - Class: rviz/Help
+    Name: Help
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+Preferences:
+  PromptSaveOnExit: true
+Toolbars:
+  toolButtonStyle: 2
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/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: base_link
+      Value: true
+    - Acceleration_Scaling_Factor: 0.1
+      Class: moveit_rviz_plugin/MotionPlanning
+      Enabled: true
+      JointsTab_Use_Radians: true
+      Move Group Namespace: ""
+      MoveIt_Allow_Approximate_IK: false
+      MoveIt_Allow_External_Program: false
+      MoveIt_Allow_Replanning: false
+      MoveIt_Allow_Sensor_Positioning: false
+      MoveIt_Planning_Attempts: 10
+      MoveIt_Planning_Time: 5
+      MoveIt_Use_Cartesian_Path: false
+      MoveIt_Use_Constraint_Aware_IK: false
+      MoveIt_Workspace:
+        Center:
+          X: 0
+          Y: 0
+          Z: 0
+        Size:
+          X: 2
+          Y: 2
+          Z: 2
+      Name: MotionPlanning
+      Planned Path:
+        Color Enabled: false
+        Interrupt Display: false
+        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
+          link_end:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+          link_flp:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+        Loop Animation: true
+        Robot Alpha: 0.5
+        Robot Color: 150; 50; 150
+        Show Robot Collision: false
+        Show Robot Visual: false
+        Show Trail: false
+        State Display Time: 0.05 s
+        Trail Step Size: 1
+        Trajectory Topic: move_group/display_planned_path
+        Use Sim Time: false
+      Planning Metrics:
+        Payload: 1
+        Show Joint Torques: false
+        Show Manipulability: false
+        Show Manipulability Index: false
+        Show Weight Limit: false
+        TextHeight: 0.07999999821186066
+      Planning Request:
+        Colliding Link Color: 255; 0; 0
+        Goal State Alpha: 1
+        Goal State Color: 250; 128; 0
+        Interactive Marker Size: 0
+        Joint Violation Color: 255; 0; 255
+        Planning Group: manipulator
+        Query Goal State: false
+        Query Start State: false
+        Show Workspace: false
+        Start State Alpha: 1
+        Start State Color: 0; 255; 0
+      Planning Scene Topic: move_group/monitored_planning_scene
+      Robot Description: robot_description
+      Scene Geometry:
+        Scene Alpha: 1
+        Scene Color: 50; 230; 50
+        Scene Display Time: 0.009999999776482582
+        Show Scene Geometry: true
+        Voxel Coloring: Z-Axis
+        Voxel Rendering: Occupied Voxels
+      Scene Robot:
+        Attached Body Color: 150; 50; 150
+        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
+          link_end:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+          link_flp:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+        Robot Alpha: 0.5
+        Show Robot Collision: false
+        Show Robot Visual: false
+      Value: true
+      Velocity_Scaling_Factor: 0.1
+    - Alpha: 1
+      Class: rviz/RobotModel
+      Collision Enabled: false
+      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
+        link_end:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        link_flp:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+      Name: RobotModel
+      Robot Description: robot_description
+      TF Prefix: ""
+      Update Interval: 0
+      Value: true
+      Visual Enabled: true
+    - Class: rviz/TF
+      Enabled: true
+      Filter (blacklist): ""
+      Filter (whitelist): ""
+      Frame Timeout: 15
+      Frames:
+        All Enabled: false
+        base_link:
+          Value: false
+        link1:
+          Value: false
+        link2:
+          Value: false
+        link3:
+          Value: false
+        link4:
+          Value: false
+        link5:
+          Value: false
+        link6:
+          Value: false
+        link_end:
+          Value: true
+        link_flp:
+          Value: true
+      Marker Alpha: 1
+      Marker Scale: 0.10000000149011612
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        base_link:
+          link1:
+            link2:
+              link3:
+                link4:
+                  link5:
+                    link6:
+                      link_flp:
+                        link_end:
+                          {}
+      Update Interval: 0
+      Value: true
+    - Class: rviz/MarkerArray
+      Enabled: true
+      Marker Topic: /rviz_visual_tools
+      Name: MarkerArray
+      Namespaces:
+        {}
+      Queue Size: 100
+      Value: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Default Light: true
+    Fixed Frame: base_link
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 3.133779287338257
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.05999999865889549
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Field of View: 0.75
+      Focal Point:
+        X: 0.9067579507827759
+        Y: 0.16720886528491974
+        Z: 0.745370626449585
+      Focal Shape Fixed Size: true
+      Focal Shape Size: 0.05000000074505806
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.009999999776482582
+      Pitch: 0.20000101625919342
+      Target Frame: base_link
+      Yaw: 4.729917526245117
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 1043
+  Help:
+    collapsed: false
+  Hide Left Dock: false
+  Hide Right Dock: false
+  MotionPlanning:
+    collapsed: false
+  MotionPlanning - Trajectory Slider:
+    collapsed: false
+  QMainWindow State: 000000ff00000000fd0000000100000000000001f3000003bdfc0200000007fb000000100044006900730070006c006100790073010000003b000003bd000000c700fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670000000208000001ee0000016900ffffff00000587000003bd00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Views:
+    collapsed: false
+  Width: 1920
+  X: 70
+  Y: 27

+ 15 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/moveit_rviz.launch

@@ -0,0 +1,15 @@
+<launch>
+
+  <arg name="debug" default="false" />
+  <arg unless="$(arg debug)" name="launch_prefix" value="" />
+  <arg     if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
+
+  <arg name="rviz_config" default="" />
+  <arg     if="$(eval rviz_config=='')" name="command_args" value="" />
+  <arg unless="$(eval rviz_config=='')" name="command_args" value="-d $(arg rviz_config)" />
+
+  <node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false"
+        args="$(arg command_args)" output="screen">
+  </node>
+
+</launch>

+ 20 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml

@@ -0,0 +1,20 @@
+<launch>
+  <!-- load OMPL planning pipeline, but add the CHOMP planning adapter. -->
+  <include file="$(find yunhua_1006a_moveit_config)/launch/ompl_planning_pipeline.launch.xml">
+    <arg name="planning_adapters"
+         default="default_planner_request_adapters/LimitMaxCartesianLinkSpeed
+                  default_planner_request_adapters/AddTimeParameterization
+                  default_planner_request_adapters/FixWorkspaceBounds
+                  default_planner_request_adapters/FixStartStateBounds
+                  default_planner_request_adapters/FixStartStateCollision
+                  default_planner_request_adapters/FixStartStatePathConstraints
+                  chomp/OptimizerAdapter"
+                  />
+  </include>
+
+  <!-- load chomp config -->
+  <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/chomp_planning.yaml" />
+
+  <!-- override trajectory_initialization_method: Use OMPL-generated trajectory -->
+  <param name="trajectory_initialization_method" value="fillTrajectory"/>
+</launch>

+ 24 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/ompl_planning_pipeline.launch.xml

@@ -0,0 +1,24 @@
+<launch>
+
+  <!-- The request adapters (plugins) used when planning with OMPL. ORDER MATTERS! -->
+  <arg name="planning_adapters"
+       default="default_planner_request_adapters/LimitMaxCartesianLinkSpeed
+                default_planner_request_adapters/AddTimeParameterization
+                default_planner_request_adapters/ResolveConstraintFrames
+                default_planner_request_adapters/FixWorkspaceBounds
+                default_planner_request_adapters/FixStartStateBounds
+                default_planner_request_adapters/FixStartStateCollision
+                default_planner_request_adapters/FixStartStatePathConstraints"
+                />
+
+  <arg name="start_state_max_bounds_error" default="0.1" />
+  <arg name="jiggle_fraction" default="0.05" />
+
+  <param name="planning_plugin" value="ompl_interface/OMPLPlanner" />
+  <param name="request_adapters" value="$(arg planning_adapters)" />
+  <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
+  <param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
+
+  <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/ompl_planning.yaml"/>
+
+</launch>

+ 15 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml

@@ -0,0 +1,15 @@
+<launch>
+
+  <!-- The request adapters (plugins) used when planning. ORDER MATTERS! -->
+  <arg name="planning_adapters" default="" />
+
+  <param name="planning_plugin" value="pilz_industrial_motion_planner::CommandPlanner" />
+  <param name="request_adapters" value="$(arg planning_adapters)" />
+
+  <!-- Define default planner (for all groups) -->
+  <param name="default_planner_config" value="PTP" />
+
+  <!-- MoveGroup capabilities to load for this pipeline, append sequence capability -->
+  <param name="capabilities" value="pilz_industrial_motion_planner/MoveGroupSequenceAction
+                                    pilz_industrial_motion_planner/MoveGroupSequenceService" />
+</launch>

+ 26 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/planning_context.launch

@@ -0,0 +1,26 @@
+<launch>
+  <!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
+  <arg name="load_robot_description" default="false"/>
+
+  <!-- The name of the parameter under which the URDF is loaded -->
+  <arg name="robot_description" default="robot_description"/>
+
+  <!-- Load universal robot description format (URDF) -->
+  <param if="$(arg load_robot_description)" name="$(arg robot_description)" textfile="$(find yunhua_ryhj)/urdf/yunhua_ryhj.urdf"/>
+
+  <!-- The semantic description that corresponds to the URDF -->
+  <param name="$(arg robot_description)_semantic" textfile="$(find yunhua_1006a_moveit_config)/config/yunhua_ryhj.srdf" />
+
+  <!-- Load updated joint limits (override information from URDF) -->
+  <group ns="$(arg robot_description)_planning">
+    <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/joint_limits.yaml"/>
+    <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/cartesian_limits.yaml"/>
+  </group>
+
+  <!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
+  <group ns="$(arg robot_description)_kinematics">
+    <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/kinematics.yaml"/>
+
+  </group>
+
+</launch>

+ 10 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/planning_pipeline.launch.xml

@@ -0,0 +1,10 @@
+<launch>
+
+  <!-- This file makes it easy to include different planning pipelines;
+       It is assumed that all planning pipelines are named XXX_planning_pipeline.launch  -->
+
+  <arg name="pipeline" default="ompl" />
+
+  <include ns="$(arg pipeline)" file="$(dirname)/$(arg pipeline)_planning_pipeline.launch.xml" />
+
+</launch>

+ 4 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml

@@ -0,0 +1,4 @@
+<launch>
+	<!-- Define MoveIt controller manager plugin -->
+	<param name="moveit_controller_manager" value="moveit_ros_control_interface::MoveItControllerManager" />
+</launch>

+ 11 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/ros_controllers.launch

@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<launch>
+
+  <!-- Load joint controller configurations from YAML file to parameter server -->
+  <rosparam file="$(find yunhua_1006a_moveit_config)/config/ros_controllers.yaml" command="load"/>
+
+  <!-- Load the controllers -->
+  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+    output="screen" args=""/>
+
+</launch>

+ 21 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/run_benchmark_ompl.launch

@@ -0,0 +1,21 @@
+<launch>
+
+  <!-- This argument must specify the list of .cfg files to process for benchmarking -->
+  <arg name="cfg" />
+
+  <!-- Load URDF -->
+  <include file="$(dirname)/planning_context.launch">
+    <arg name="load_robot_description" value="true"/>
+  </include>
+
+  <!-- Start the database -->
+  <include file="$(dirname)/warehouse.launch">
+    <arg name="moveit_warehouse_database_path" value="moveit_ompl_benchmark_warehouse"/>
+  </include>
+
+  <!-- Start Benchmark Executable -->
+  <node name="$(anon moveit_benchmark)" pkg="moveit_ros_benchmarks" type="moveit_run_benchmark" args="$(arg cfg) --benchmark-planners" respawn="false" output="screen">
+    <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/ompl_planning.yaml"/>
+  </node>
+
+</launch>

+ 17 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/sensor_manager.launch.xml

@@ -0,0 +1,17 @@
+<launch>
+
+  <!-- This file makes it easy to include the settings for sensor managers -->
+
+  <!-- Params for 3D sensors config -->
+  <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/sensors_3d.yaml" />
+
+  <!-- Params for the octomap monitor -->
+  <!--  <param name="octomap_frame" type="string" value="some frame in which the robot moves" /> -->
+  <param name="octomap_resolution" type="double" value="0.003" />
+  <param name="max_range" type="double" value="5.0" />
+
+  <!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter -->
+  <arg name="moveit_sensor_manager" default="yunhua_ryhj" />
+  <include file="$(dirname)/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" />
+
+</launch>

+ 16 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/setup_assistant.launch

@@ -0,0 +1,16 @@
+<!-- Re-launch the MoveIt Setup Assistant with this configuration package already loaded -->
+<launch>
+
+  <!-- Debug Info -->
+  <arg name="debug" default="false" />
+  <arg unless="$(arg debug)" name="launch_prefix" value="" />
+  <arg     if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
+
+  <!-- Run -->
+  <node pkg="moveit_setup_assistant" type="moveit_setup_assistant" name="moveit_setup_assistant"
+        args="--config_pkg=yunhua_1006a_moveit_config"
+        launch-prefix="$(arg launch_prefix)"
+        required="true"
+        output="screen" />
+
+</launch>

+ 8 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/simple_moveit_controller_manager.launch.xml

@@ -0,0 +1,8 @@
+<launch>
+  <!-- Define the MoveIt controller manager plugin to use for trajectory execution -->
+  <param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
+
+  <!-- Load controller list to the parameter server -->
+  <rosparam file="$(find yunhua_1006a_moveit_config)/config/simple_moveit_controllers.yaml" />
+  <rosparam file="$(find yunhua_1006a_moveit_config)/config/ros_controllers.yaml" />
+</launch>

+ 23 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/stomp_planning_pipeline.launch.xml

@@ -0,0 +1,23 @@
+<launch>
+  <!-- Stomp Plugin for MoveIt -->
+  <arg name="planning_plugin" value="stomp_moveit/StompPlannerManager" />
+
+  <arg name="start_state_max_bounds_error" value="0.1" />
+  <arg name="jiggle_fraction" value="0.05" />
+  <!-- The request adapters (plugins) used when planning. ORDER MATTERS! -->
+  <arg name="planning_adapters"
+       default="default_planner_request_adapters/LimitMaxCartesianLinkSpeed
+                default_planner_request_adapters/AddTimeParameterization
+                default_planner_request_adapters/FixWorkspaceBounds
+                default_planner_request_adapters/FixStartStateBounds
+                default_planner_request_adapters/FixStartStateCollision
+                default_planner_request_adapters/FixStartStatePathConstraints" />
+
+
+  <param name="planning_plugin" value="$(arg planning_plugin)" />
+  <param name="request_adapters" value="$(arg planning_adapters)" />
+  <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />
+  <param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
+
+  <rosparam command="load" file="$(find yunhua_1006a_moveit_config)/config/stomp_planning.yaml"/>
+</launch>

+ 23 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/trajectory_execution.launch.xml

@@ -0,0 +1,23 @@
+<launch>
+  <!-- This file summarizes all settings required for trajectory execution  -->
+
+  <!-- Define moveit controller manager plugin: fake, simple, or ros_control -->
+  <arg name="moveit_controller_manager" />
+  <arg name="fake_execution_type" default="interpolate" />
+
+  <!-- Flag indicating whether MoveIt is allowed to load/unload  or switch controllers -->
+  <arg name="moveit_manage_controllers" default="true"/>
+  <param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/>
+
+  <!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
+  <param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
+  <!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
+  <param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
+  <!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->
+  <param name="trajectory_execution/allowed_start_tolerance" value="0.01"/> <!-- default 0.01 -->
+
+  <!-- We use pass_all_args=true here to pass fake_execution_type, which is required by fake controllers, but not by real-robot controllers.
+       As real-robot controller_manager.launch files shouldn't be required to define this argument, we use the trick of passing all args. -->
+  <include file="$(dirname)/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" pass_all_args="true" />
+
+</launch>

+ 15 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/warehouse.launch

@@ -0,0 +1,15 @@
+<launch>
+
+  <!-- The path to the database must be specified -->
+  <arg name="moveit_warehouse_database_path" />
+
+  <!-- Load warehouse parameters -->
+  <include file="$(dirname)/warehouse_settings.launch.xml" />
+
+  <!-- Run the DB server -->
+  <node name="$(anon mongo_wrapper_ros)" cwd="ROS_HOME" type="mongo_wrapper_ros.py" pkg="warehouse_ros_mongo">
+    <param name="overwrite" value="false"/>
+    <param name="database_path" value="$(arg moveit_warehouse_database_path)" />
+  </node>
+
+</launch>

+ 16 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/warehouse_settings.launch.xml

@@ -0,0 +1,16 @@
+<launch>
+  <!-- Set the parameters for the warehouse and run the mongodb server. -->
+
+  <!-- The default DB port for moveit (not default MongoDB port to avoid potential conflicts) -->
+  <arg name="moveit_warehouse_port" default="33829" />
+
+  <!-- The default DB host for moveit -->
+  <arg name="moveit_warehouse_host" default="localhost" />
+
+  <!-- Set parameters for the warehouse -->
+  <param name="warehouse_port" value="$(arg moveit_warehouse_port)"/>
+  <param name="warehouse_host" value="$(arg moveit_warehouse_host)"/>
+  <param name="warehouse_exec" value="mongod" />
+  <param name="warehouse_plugin" value="warehouse_ros_mongo::MongoDatabaseConnection" />
+
+</launch>

+ 3 - 0
catkin_ws/src/yunhua_1006a_moveit_config/launch/yunhua_ryhj_moveit_sensor_manager.launch.xml

@@ -0,0 +1,3 @@
+<launch>
+
+</launch>

+ 41 - 0
catkin_ws/src/yunhua_1006a_moveit_config/package.xml

@@ -0,0 +1,41 @@
+<package>
+
+  <name>yunhua_1006a_moveit_config</name>
+  <version>0.3.0</version>
+  <description>
+     An automatically generated package with all the configuration and launch files for using the yunhua_ryhj with the MoveIt Motion Planning Framework
+  </description>
+  <author email="123@163.com">123</author>
+  <maintainer email="123@163.com">123</maintainer>
+
+  <license>BSD</license>
+
+  <url type="website">http://moveit.ros.org/</url>
+  <url type="bugtracker">https://github.com/moveit/moveit/issues</url>
+  <url type="repository">https://github.com/moveit/moveit</url>
+
+  <buildtool_depend>catkin</buildtool_depend>
+
+  <run_depend>moveit_ros_move_group</run_depend>
+  <run_depend>moveit_fake_controller_manager</run_depend>
+  <run_depend>moveit_kinematics</run_depend>
+  <run_depend>moveit_planners</run_depend>
+  <run_depend>moveit_ros_visualization</run_depend>
+  <run_depend>moveit_setup_assistant</run_depend>
+  <run_depend>moveit_simple_controller_manager</run_depend>
+  <run_depend>joint_state_publisher</run_depend>
+  <run_depend>joint_state_publisher_gui</run_depend>
+  <run_depend>robot_state_publisher</run_depend>
+  <run_depend>rviz</run_depend>
+  <run_depend>tf2_ros</run_depend>
+  <run_depend>xacro</run_depend>
+  <!-- The next 2 packages are required for the gazebo simulation.
+       We don't include them by default to prevent installing gazebo and all its dependencies. -->
+  <!-- <run_depend>joint_trajectory_controller</run_depend> -->
+  <!-- <run_depend>gazebo_ros_control</run_depend> -->
+  <!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->
+  <!-- <run_depend>warehouse_ros_mongo</run_depend> -->
+  <run_depend>yunhua_ryhj</run_depend>
+
+
+</package>

+ 14 - 0
catkin_ws/src/yunhua_ryhj/CMakeLists.txt

@@ -0,0 +1,14 @@
+cmake_minimum_required(VERSION 2.8.3)
+
+project(yunhua_ryhj)
+
+find_package(catkin REQUIRED)
+
+catkin_package()
+
+find_package(roslaunch)
+
+foreach(dir config launch meshes urdf)
+	install(DIRECTORY ${dir}/
+		DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
+endforeach(dir)

+ 1 - 0
catkin_ws/src/yunhua_ryhj/config/joint_names_yunhua_ryhj.yaml

@@ -0,0 +1 @@
+controller_joint_names: ['', 'joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6', ]

+ 20 - 0
catkin_ws/src/yunhua_ryhj/launch/display.launch

@@ -0,0 +1,20 @@
+<launch>
+  <arg
+    name="model" />
+  <param
+    name="robot_description"
+    textfile="$(find yunhua_ryhj)/urdf/yunhua_ryhj.urdf" />
+  <node
+    name="joint_state_publisher_gui"
+    pkg="joint_state_publisher_gui"
+    type="joint_state_publisher_gui" />
+  <node
+    name="robot_state_publisher"
+    pkg="robot_state_publisher"
+    type="robot_state_publisher" />
+  <node
+    name="rviz"
+    pkg="rviz"
+    type="rviz"
+    args="-d $(find yunhua_ryhj)/urdf.rviz" />
+</launch>

+ 20 - 0
catkin_ws/src/yunhua_ryhj/launch/gazebo.launch

@@ -0,0 +1,20 @@
+<launch>
+  <include
+    file="$(find gazebo_ros)/launch/empty_world.launch" />
+  <node
+    name="tf_footprint_base"
+    pkg="tf"
+    type="static_transform_publisher"
+    args="0 0 0 0 0 0 base_link base_footprint 40" />
+  <node
+    name="spawn_model"
+    pkg="gazebo_ros"
+    type="spawn_model"
+    args="-file $(find yunhua_ryhj)/urdf/yunhua_ryhj.urdf -urdf -model yunhua_ryhj"
+    output="screen" />
+  <node
+    name="fake_joint_calibration"
+    pkg="rostopic"
+    type="rostopic"
+    args="pub /calibrated std_msgs/Bool true" />
+</launch>

BIN
catkin_ws/src/yunhua_ryhj/meshes/base_link.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link1.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link2.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link3.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link4.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link5.STL


BIN
catkin_ws/src/yunhua_ryhj/meshes/link6.STL


+ 21 - 0
catkin_ws/src/yunhua_ryhj/package.xml

@@ -0,0 +1,21 @@
+<package format="2">
+  <name>yunhua_ryhj</name>
+  <version>1.0.0</version>
+  <description>
+    <p>URDF Description package for yunhua_ryhj</p>
+    <p>This package contains configuration data, 3D models and launch files
+for yunhua_ryhj robot</p>
+  </description>
+  <author>TODO</author>
+  <maintainer email="TODO@email.com" />
+  <license>BSD</license>
+  <buildtool_depend>catkin</buildtool_depend>
+  <depend>roslaunch</depend>
+  <depend>robot_state_publisher</depend>
+  <depend>rviz</depend>
+  <depend>joint_state_publisher_gui</depend>
+  <depend>gazebo</depend>
+  <export>
+    <architecture_independent />
+  </export>
+</package>

+ 8 - 0
catkin_ws/src/yunhua_ryhj/urdf/yunhua_ryhj.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.073946,-7.5783E-05,0.079686,0,0,0,26.825,0.29447,-0.00068906,-0.0018702,0.70624,8.3009E-05,0.88713,0,0,0,0,0,0,package://yunhua_ryhj/meshes/base_link.STL,0.1451,0.1451,0.1451,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/base_link.STL,,HY1020A-180-1-1,基坐标系,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
+link1,0.040145,-0.0017665,-0.17281,0,0,0,39.487,0.98418,-0.16112,-0.47642,1.5184,-0.10144,1.2525,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link1.STL,1,1,1,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link1.STL,,HY1020A-180-2-1;送丝盘SLDPRT-1,坐标系1,轴1,joint1,revolute,0,0,0.511,0,0,0,base_link,0,0,-1,0,0,-3.14,3.14,,,,,,,,
+link2,-0.030086,0.33235,0.14338,0,0,0,11.602,0.54948,0.0072392,0.0022966,0.040699,-0.0016648,0.56667,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link2.STL,1,0,0,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link2.STL,,HY1010A-180-3-1,坐标系2,轴2,joint2,revolute,0.225,0,0,1.5708,0,0,link1,0,0,-1,0,0,-3.14,3.14,,,,,,,,
+link3,0.080981,0.12571,-9.0574E-05,0,0,0,13.961,0.19012,-0.11007,0.0065658,0.19149,0.011087,0.28951,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link3.STL,1,1,1,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link3.STL,,HY1010A-180-4-1;送丝机-1,坐标系3,轴3,joint3,revolute,0,0.76,0,0,0,0,link2,0,0,1,0,0,-3.14,3.14,,,,,,,,
+link4,-0.0016575,0.026244,0.35186,0,0,0,10.585,0.16278,0.00030377,0.0018777,0.18729,-0.010668,0.051504,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link4.STL,1,0,0,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link4.STL,,HY1006A-200-1-1;HY1006A-144-5-1,坐标系4,轴4,joint4,revolute,0.9915,0.215,0,0,-1.5708,0,link3,0,0,-1,0,0,-3.14,3.14,,,,,,,,
+link5,-5.2388E-05,-0.061382,-0.0003515,0,0,0,1.0093,0.0042625,6.072E-07,-2.4533E-07,0.0023268,-0.00020667,0.0032649,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link5.STL,1,0,0,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link5.STL,,HY1006A-138-6-1,坐标系5,轴5,joint5,revolute,0,0,0,0,1.5708,0,link4,0,0,1,0,0,-3.14,3.14,,,,,,,,
+link6,-0.073417,-0.00013522,0.2336,0,0,0,0.62764,0.0028394,1.5554E-06,0.00027709,0.0011602,-4.9029E-08,0.0030715,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link6.STL,0.75294,0.75294,0.75294,1,0,0,0,0,0,0,package://yunhua_ryhj/meshes/link6.STL,,焊枪_LST-1,坐标系6,轴6,joint6,revolute,0,0,0,1.5708,0,0,link5,0,0,-1,0,0,-3.14,3.14,,,,,,,,

+ 420 - 0
catkin_ws/src/yunhua_ryhj/urdf/yunhua_ryhj.urdf

@@ -0,0 +1,420 @@
+<?xml version="1.0" encoding="utf-8"?>
+<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
+     Commit Version: 1.6.0-4-g7f85cfe  Build Version: 1.6.7995.38578
+     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
+<robot
+  name="yunhua_ryhj">
+  <link
+    name="base_link">
+    <!-- <inertial>
+      <origin
+        xyz="-0.073946 -7.5783E-05 0.079686"
+        rpy="0 0 0" />
+      <mass
+        value="26.825" />
+      <inertia
+        ixx="0.29447"
+        ixy="-0.00068906"
+        ixz="-0.0018702"
+        iyy="0.70624"
+        iyz="8.3009E-05"
+        izz="0.88713" />
+    </inertial> -->
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/base_link.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="0.1451 0.1451 0.1451 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/base_link.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <link
+    name="link1">
+    <inertial>
+      <origin
+        xyz="0.040145 -0.0017665 -0.17281"
+        rpy="0 0 0" />
+      <mass
+        value="39.487" />
+      <inertia
+        ixx="0.98418"
+        ixy="-0.16112"
+        ixz="-0.47642"
+        iyy="1.5184"
+        iyz="-0.10144"
+        izz="1.2525" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link1.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 1 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link1.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint1"
+    type="revolute">
+    <origin
+      xyz="0 0 0.511"
+      rpy="0 0 0" />
+    <parent
+      link="base_link" />
+    <child
+      link="link1" />
+    <axis
+      xyz="0 0 1" />
+    <limit
+      lower="-2.617995"
+      upper="2.617995"
+      effort="0"
+      velocity="2.827" />
+  </joint>
+  <link
+    name="link2">
+    <inertial>
+      <origin
+        xyz="-0.030086 0.33235 0.14338"
+        rpy="0 0 0" />
+      <mass
+        value="11.602" />
+      <inertia
+        ixx="0.54948"
+        ixy="0.0072392"
+        ixz="0.0022966"
+        iyy="0.040699"
+        iyz="-0.0016648"
+        izz="0.56667" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link2.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 0 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link2.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint2"
+    type="revolute">
+    <origin
+      xyz="0.225 0 0"
+      rpy="1.5708 0 0" />
+    <parent
+      link="link1" />
+    <child
+      link="link2" />
+    <axis
+      xyz="0 0 -1" />
+    <limit
+      lower="-1.448624"
+      upper="1.570797"
+      effort="0"
+      velocity="2.827" />
+  </joint>
+  <link
+    name="link3">
+    <inertial>
+      <origin
+        xyz="0.080981 0.12571 -9.0574E-05"
+        rpy="0 0 0" />
+      <mass
+        value="13.961" />
+      <inertia
+        ixx="0.19012"
+        ixy="-0.11007"
+        ixz="0.0065658"
+        iyy="0.19149"
+        iyz="0.011087"
+        izz="0.28951" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link3.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 1 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link3.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint3"
+    type="revolute">
+    <origin
+      xyz="0 0.76 0"
+      rpy="0 0 0" />
+    <parent
+      link="link2" />
+    <child
+      link="link3" />
+    <axis
+      xyz="0 0 -1" />
+    <limit
+      lower="-1.308998"
+      upper="1.186824"
+      effort="0"
+      velocity="3.463" />
+  </joint>
+  <link
+    name="link4">
+    <inertial>
+      <origin
+        xyz="-0.0016575 0.026244 0.35186"
+        rpy="0 0 0" />
+      <mass
+        value="10.585" />
+      <inertia
+        ixx="0.16278"
+        ixy="0.00030377"
+        ixz="0.0018777"
+        iyy="0.18729"
+        iyz="-0.010668"
+        izz="0.051504" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link4.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 0 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link4.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint4"
+    type="revolute">
+    <origin
+      xyz="0.9915 0.215 0"
+      rpy="0 -1.5708 0" />
+    <parent
+      link="link3" />
+    <child
+      link="link4" />
+    <axis
+      xyz="0 0 -1" />
+    <limit
+      lower="-2.3"
+      upper="2.3"
+      effort="0"
+      velocity="7.106" />
+  </joint>
+  <link
+    name="link5">
+    <inertial>
+      <origin
+        xyz="-5.2388E-05 -0.061382 -0.0003515"
+        rpy="0 0 0" />
+      <mass
+        value="1.0093" />
+      <inertia
+        ixx="0.0042625"
+        ixy="6.072E-07"
+        ixz="-2.4533E-07"
+        iyy="0.0023268"
+        iyz="-0.00020667"
+        izz="0.0032649" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link5.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 0 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link5.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint5"
+    type="revolute">
+    <origin
+      xyz="0 0 0"
+      rpy="-1.5708 3.1416 -1.5708" />
+    <parent
+      link="link4" />
+    <child
+      link="link5" />
+    <axis
+      xyz="0 0 -1" />
+    <limit
+      lower="-1.570797"
+      upper="2.268929"
+      effort="0"
+      velocity="5.639" />
+  </joint>
+  <link
+    name="link6">
+    <inertial>
+      <origin
+        xyz="-0.073417 -0.00013522 0.2336"
+        rpy="0 0 0" />
+      <mass
+        value="0.62764" />
+      <inertia
+        ixx="0.0028394"
+        ixy="1.5554E-06"
+        ixz="0.00027709"
+        iyy="0.0011602"
+        iyz="-4.9029E-08"
+        izz="0.0030715" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link6.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="0.75294 0.75294 0.75294 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://yunhua_ryhj/meshes/link6.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint6"
+    type="revolute">
+    <origin
+      xyz="0 0 0"
+      rpy="1.5708 0 0" />
+    <parent
+      link="link5" />
+    <child
+      link="link6" />
+    <axis
+      xyz="0 0 1" />
+    <limit
+      lower="-3.839726"
+      upper="3.839726"
+      effort="0"
+      velocity="0" />
+  </joint>
+
+    <link name="link_flp">
+    <collision>
+      <geometry>
+        <box size="0.0001 0.0001 0.0001"/>
+      </geometry>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </collision>
+  </link>
+
+  <joint name="joint_flp" type="fixed">
+    <parent link="link6"/>
+    <child link="link_flp"/>
+    <origin rpy="0 0 3.1415926" xyz="0 0 0.140"/>
+  </joint>
+
+  <link name="link_end">
+  </link>
+
+  <joint name="joint_end" type="fixed">
+    <parent link="link_flp"/>
+    <child link="link_end"/>
+    <origin rpy="0.0 0.0 3.1415926" xyz="-0.1374835  0.0041203  0.3690754"/>
+  </joint>
+
+</robot>