Browse Source

2024-9-27

bzx 8 months ago
parent
commit
6a2ece715a
79 changed files with 4291 additions and 0 deletions
  1. 1 0
      ren_yuan/.catkin_workspace
  2. 1 0
      ren_yuan/cmd.txt
  3. 1 0
      ren_yuan/src/CMakeLists.txt
  4. 14 0
      ren_yuan/src/a9/CMakeLists.txt
  5. 1 0
      ren_yuan/src/a9/config/joint_names_a9.yaml
  6. 20 0
      ren_yuan/src/a9/launch/display.launch
  7. 20 0
      ren_yuan/src/a9/launch/gazebo.launch
  8. BIN
      ren_yuan/src/a9/meshes/Link_1.STL
  9. BIN
      ren_yuan/src/a9/meshes/Link_2.STL
  10. BIN
      ren_yuan/src/a9/meshes/Link_3.STL
  11. BIN
      ren_yuan/src/a9/meshes/Link_4.STL
  12. BIN
      ren_yuan/src/a9/meshes/Link_5.STL
  13. BIN
      ren_yuan/src/a9/meshes/Link_6.STL
  14. BIN
      ren_yuan/src/a9/meshes/Link_7.STL
  15. BIN
      ren_yuan/src/a9/meshes/base_link.STL
  16. 21 0
      ren_yuan/src/a9/package.xml
  17. 9 0
      ren_yuan/src/a9/urdf/a9.csv
  18. 465 0
      ren_yuan/src/a9/urdf/a9.urdf
  19. 224 0
      ren_yuan/src/lst_robot_r/CMakeLists.txt
  20. 5 0
      ren_yuan/src/lst_robot_r/launch/start.launch
  21. 7 0
      ren_yuan/src/lst_robot_r/msg/JointTrajectoryPoint_ex.msg
  22. 3 0
      ren_yuan/src/lst_robot_r/msg/JointTrajectory_ex.msg
  23. 70 0
      ren_yuan/src/lst_robot_r/package.xml
  24. 70 0
      ren_yuan/src/lst_robot_r/scripts/CloudFunc.py
  25. 145 0
      ren_yuan/src/lst_robot_r/scripts/check.py
  26. 50 0
      ren_yuan/src/lst_robot_r/scripts/command.py
  27. 16 0
      ren_yuan/src/lst_robot_r/scripts/decorator_time.py
  28. 162 0
      ren_yuan/src/lst_robot_r/scripts/dycl_0506.py
  29. 89 0
      ren_yuan/src/lst_robot_r/scripts/hanqiangpose.py
  30. 143 0
      ren_yuan/src/lst_robot_r/scripts/hjsx.py
  31. 512 0
      ren_yuan/src/lst_robot_r/scripts/moveitServer2.py
  32. 48 0
      ren_yuan/src/lst_robot_r/scripts/redis_publisher.py
  33. 130 0
      ren_yuan/src/lst_robot_r/scripts/start.py
  34. 11 0
      ren_yuan/src/lstrobot_moveit_config_0605/.setup_assistant
  35. 10 0
      ren_yuan/src/lstrobot_moveit_config_0605/CMakeLists.txt
  36. 48 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/a9.srdf
  37. 5 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/cartesian_limits.yaml
  38. 18 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/chomp_planning.yaml
  39. 13 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/fake_controllers.yaml
  40. 296 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/gazebo_a9.urdf
  41. 4 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/gazebo_controllers.yaml
  42. 40 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/joint_limits.yaml
  43. 7 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/kinematics.yaml
  44. 198 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/ompl_planning.yaml
  45. 0 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/ros_controllers.yaml
  46. 10 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/sensors_3d.yaml
  47. 10 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/sensors_3d2.yaml
  48. 2 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/simple_moveit_controllers.yaml
  49. 39 0
      ren_yuan/src/lstrobot_moveit_config_0605/config/stomp_planning.yaml
  50. 3 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/a9_moveit_sensor_manager.launch.xml
  51. 21 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/chomp_planning_pipeline.launch.xml
  52. 15 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/default_warehouse_db.launch
  53. 66 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/demo.launch
  54. 21 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/demo_gazebo.launch
  55. 12 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/fake_moveit_controller_manager.launch.xml
  56. 34 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/gazebo.launch
  57. 17 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/joystick_control.launch
  58. 105 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/move_group.launch
  59. 386 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/moveit.rviz
  60. 15 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/moveit_rviz.launch
  61. 20 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/ompl-chomp_planning_pipeline.launch.xml
  62. 24 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/ompl_planning_pipeline.launch.xml
  63. 15 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
  64. 26 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/planning_context.launch
  65. 10 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/planning_pipeline.launch.xml
  66. 4 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/ros_control_moveit_controller_manager.launch.xml
  67. 11 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/ros_controllers.launch
  68. 21 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/run_benchmark_ompl.launch
  69. 17 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/sensor_manager.launch.xml
  70. 16 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/setup_assistant.launch
  71. 8 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/simple_moveit_controller_manager.launch.xml
  72. 23 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/stomp_planning_pipeline.launch.xml
  73. 23 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/trajectory_execution.launch.xml
  74. 15 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/warehouse.launch
  75. 16 0
      ren_yuan/src/lstrobot_moveit_config_0605/launch/warehouse_settings.launch.xml
  76. 41 0
      ren_yuan/src/lstrobot_moveit_config_0605/package.xml
  77. 49 0
      ren_yuan/src/visual/CMakeLists.txt
  78. 68 0
      ren_yuan/src/visual/package.xml
  79. 251 0
      ren_yuan/src/visual/src/visual_tools.cpp

+ 1 - 0
ren_yuan/.catkin_workspace

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

+ 1 - 0
ren_yuan/cmd.txt

@@ -0,0 +1 @@
+roslaunch lst_robot_r start.launch

+ 1 - 0
ren_yuan/src/CMakeLists.txt

@@ -0,0 +1 @@
+/opt/ros/noetic/share/catkin/cmake/toplevel.cmake

+ 14 - 0
ren_yuan/src/a9/CMakeLists.txt

@@ -0,0 +1,14 @@
+cmake_minimum_required(VERSION 2.8.3)
+
+project(a9)
+
+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
ren_yuan/src/a9/config/joint_names_a9.yaml

@@ -0,0 +1 @@
+controller_joint_names: ['', 'joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6', ]

+ 20 - 0
ren_yuan/src/a9/launch/display.launch

@@ -0,0 +1,20 @@
+<launch>
+  <arg
+    name="model" />
+  <param
+    name="robot_description"
+    textfile="$(find a9)/urdf/a9.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 a9)/urdf.rviz" />
+</launch>

+ 20 - 0
ren_yuan/src/a9/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 a9)/urdf/a9.urdf -urdf -model a9"
+    output="screen" />
+  <node
+    name="fake_joint_calibration"
+    pkg="rostopic"
+    type="rostopic"
+    args="pub /calibrated std_msgs/Bool true" />
+</launch>

BIN
ren_yuan/src/a9/meshes/Link_1.STL


BIN
ren_yuan/src/a9/meshes/Link_2.STL


BIN
ren_yuan/src/a9/meshes/Link_3.STL


BIN
ren_yuan/src/a9/meshes/Link_4.STL


BIN
ren_yuan/src/a9/meshes/Link_5.STL


BIN
ren_yuan/src/a9/meshes/Link_6.STL


BIN
ren_yuan/src/a9/meshes/Link_7.STL


BIN
ren_yuan/src/a9/meshes/base_link.STL


+ 21 - 0
ren_yuan/src/a9/package.xml

@@ -0,0 +1,21 @@
+<package format="2">
+  <name>a9</name>
+  <version>1.0.0</version>
+  <description>
+    <p>URDF Description package for a9</p>
+    <p>This package contains configuration data, 3D models and launch files
+for a9 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>

+ 9 - 0
ren_yuan/src/a9/urdf/a9.csv

@@ -0,0 +1,9 @@
+Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
+base_link,-0.110121070288428,-0.0129999995820303,0.159000000973282,0,0,0,0.0148298653353077,2.02744416702812E-06,-1.54215522606031E-15,-3.37592192750916E-14,1.40267326461625E-06,-2.76126618174793E-15,1.40267288470545E-06,0,0,0,0,0,0,package://a9/meshes/base_link.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/base_link.STL,,FANUC M-10iA8L - 底座-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
+Link_1,0.802922442229256,0.00984539192698494,1.19598646678643,0,0,0,8.19341168850207,0.19323050511757,0.0386299594946521,-0.388616965148905,1.42567974975729,0.0128991341474255,1.24513273855516,0,0,0,0,0,0,package://a9/meshes/Link_1.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_1.STL,,FANUC M-10iA8L - 1-1,Origin_joint_1,Axis_joint_1,joint_1,revolute,0,0,0.278,0,0,0,base_link,0,0,1,0,0,-3,3,,,,,,,,
+Link_2,0.117746157865896,0.0426453911640452,1.20871486266949,0,0,0,8.19341168850207,0.723493788556202,0.0285843029943905,-0.653933580723206,1.42567974975729,0.0290103266895879,0.714869455116528,0,0,0,0,0,0,package://a9/meshes/Link_2.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_2.STL,,FANUC M-10iA8L - 2-1,Origin_joint_2,Axis_joint_2,joint_2,revolute,0.15,-0.0328,0.172,0,0.47052,0,Link_1,0,1,0,0,0,-3,3,,,,,,,,
+Link_3,0.00164806841162357,0.0743961632896021,-0.0125870623969895,0,0,0,1.10722558532838,0.00281804497282514,1.0820613146504E-05,-2.30905562044302E-05,0.00127732014523064,5.62797076557556E-06,0.0028367630953507,0,0,0,0,0,0,package://a9/meshes/Link_3.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_3.STL,,FANUC M-10iA8L - 3-1,Origin_joint_3,Axis_joint_3,joint_3,revolute,-0.59925,0,0.50037,0,-0.28892,0,Link_2,0,1,0,0,0,-3,3,,,,,,,,
+Link_4,0.751501000756241,-0.00505225715113682,0.690060032582326,0,0,0,8.19341168850207,0.419099372956719,-0.0348631653478693,-0.581012917159635,1.42564974048808,-0.0218580250133829,1.01929387998522,0,0,0,0,0,0,package://a9/meshes/Link_4.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_4.STL,,FANUC M-10iA8L - 4-1,Origin_joint_4,Axis_joint_4,joint_4,revolute,-0.084223,0.0347,0.16884,-3.119,-1.0471,-0.013042,Link_3,0.86603,0,0.5,0,0,-3,3,,,,,,,,
+Link_5,0.206551018322306,-0.00505225715114058,-0.104834036546721,0,0,0,8.19341168850207,0.745717188604768,0.0281122476978264,-0.653399595391099,1.42564974048808,0.030048545471202,0.69267606433717,0,0,0,0,0,0,package://a9/meshes/Link_5.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_5.STL,,FANUC M-10iA8L - 5-1,Origin_joint_5,Axis_joint_5,joint_5,revolute,0.92436,0,0.53588,3.1416,-0.25867,3.1416,Link_4,0,1,0,0,0,-3,3,,,,,,,,
+Link_6,0.12280626304832,0.10284172733946,-0.0673247079199191,0,0,0,8.19341168850207,1.25065484857243,-0.370837141231599,-0.214061773475593,0.581725625286335,-0.544088624970368,1.03166251957125,0,0,0,0,0,0,package://a9/meshes/Link_6.STL,1,1,0,1,0,0,0,0,0,0,package://a9/meshes/Link_6.STL,,FANUC M-10iA8L - 6-1,Origin_joint_6,Axis_joint_6,joint_6,revolute,0.037697,-0.0006997,-0.064094,0.44032,0.19669,-0.83053,Link_5,0.49999,0,-0.86603,0,0,-3,3,,,,,,,,
+Link_7,0.0296425829147993,-6.47728578861279E-06,0.162281442392356,0,0,0,7.07143232149748,0.0103947066541271,8.00167786886164E-07,0.00131122028195651,0.0112643862205598,-2.38846633634112E-06,0.0065729384023248,0,0,0,0,0,0,package://a9/meshes/Link_7.STL,0.752941176470588,0.752941176470588,0.752941176470588,1,0,0,0,0,0,0,package://a9/meshes/Link_7.STL,,META激光跟踪-2,Origin_joint_72,Axis_joint_7,joint_7,fixed,0,0,0,-2.6972,0.28661,-2.1066,Link_6,0,0,0,,,,,,,,,,,,

+ 465 - 0
ren_yuan/src/a9/urdf/a9.urdf

@@ -0,0 +1,465 @@
+<?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="a9">
+  <link name="world" />
+  
+  <joint name="world_joint" type="fixed">
+    <parent link="world" />
+    <child link = "base_link" />
+    <origin xyz="0.0 0.0 2.17" rpy="0.0 3.14 0.0" />
+  </joint>
+  
+  <link
+    name="base_link">
+    <inertial>
+      <origin
+        xyz="-0.110121070288428 -0.0129999995820303 0.159000000973282"
+        rpy="0 0 0" />
+      <mass
+        value="0.0148298653353077" />
+      <inertia
+        ixx="2.02744416702812E-06"
+        ixy="-1.54215522606031E-15"
+        ixz="-3.37592192750916E-14"
+        iyy="1.40267326461625E-06"
+        iyz="-2.76126618174793E-15"
+        izz="1.40267288470545E-06" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/base_link.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/base_link.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <link
+    name="Link_1">
+    <inertial>
+      <origin
+        xyz="0.802922442229256 0.00984539192698494 1.19598646678643"
+        rpy="0 0 0" />
+      <mass
+        value="8.19341168850207" />
+      <inertia
+        ixx="0.19323050511757"
+        ixy="0.0386299594946521"
+        ixz="-0.388616965148905"
+        iyy="1.42567974975729"
+        iyz="0.0128991341474255"
+        izz="1.24513273855516" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_1.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_1.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_1"
+    type="revolute">
+    <origin
+      xyz="0 0 0.278"
+      rpy="0 0 0" />
+    <parent
+      link="base_link" />
+    <child
+      link="Link_1" />
+    <axis
+      xyz="0 0 1" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_2">
+    <inertial>
+      <origin
+        xyz="0.117746157865896 0.0426453911640452 1.20871486266949"
+        rpy="0 0 0" />
+      <mass
+        value="8.19341168850207" />
+      <inertia
+        ixx="0.723493788556202"
+        ixy="0.0285843029943905"
+        ixz="-0.653933580723206"
+        iyy="1.42567974975729"
+        iyz="0.0290103266895879"
+        izz="0.714869455116528" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_2.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_2.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_2"
+    type="revolute">
+    <origin
+      xyz="0.15 -0.0328 0.172"
+      rpy="0 0.47052 0" />
+    <parent
+      link="Link_1" />
+    <child
+      link="Link_2" />
+    <axis
+      xyz="0 1 0" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_3">
+    <inertial>
+      <origin
+        xyz="0.00164806841162357 0.0743961632896021 -0.0125870623969895"
+        rpy="0 0 0" />
+      <mass
+        value="1.10722558532838" />
+      <inertia
+        ixx="0.00281804497282514"
+        ixy="1.0820613146504E-05"
+        ixz="-2.30905562044302E-05"
+        iyy="0.00127732014523064"
+        iyz="5.62797076557556E-06"
+        izz="0.0028367630953507" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_3.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_3.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_3"
+    type="revolute">
+    <origin
+      xyz="-0.59925 0 0.50037"
+      rpy="0 -0.28892 0" />
+    <parent
+      link="Link_2" />
+    <child
+      link="Link_3" />
+    <axis
+      xyz="0 1 0" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_4">
+    <inertial>
+      <origin
+        xyz="0.751501000756241 -0.00505225715113682 0.690060032582326"
+        rpy="0 0 0" />
+      <mass
+        value="8.19341168850207" />
+      <inertia
+        ixx="0.419099372956719"
+        ixy="-0.0348631653478693"
+        ixz="-0.581012917159635"
+        iyy="1.42564974048808"
+        iyz="-0.0218580250133829"
+        izz="1.01929387998522" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_4.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_4.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_4"
+    type="revolute">
+    <origin
+      xyz="-0.084223 0.0347 0.16884"
+      rpy="-3.119 -1.0471 -0.013042" />
+    <parent
+      link="Link_3" />
+    <child
+      link="Link_4" />
+    <axis
+      xyz="0.86603 0 0.5" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_5">
+    <inertial>
+      <origin
+        xyz="0.206551018322306 -0.00505225715114058 -0.104834036546721"
+        rpy="0 0 0" />
+      <mass
+        value="8.19341168850207" />
+      <inertia
+        ixx="0.745717188604768"
+        ixy="0.0281122476978264"
+        ixz="-0.653399595391099"
+        iyy="1.42564974048808"
+        iyz="0.030048545471202"
+        izz="0.69267606433717" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_5.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_5.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_5"
+    type="revolute">
+    <origin
+      xyz="0.92436 0 0.53588"
+      rpy="3.1416 -0.25867 3.1416" />
+    <parent
+      link="Link_4" />
+    <child
+      link="Link_5" />
+    <axis
+      xyz="0 1 0" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_6">
+    <inertial>
+      <origin
+        xyz="0.12280626304832 0.10284172733946 -0.0673247079199191"
+        rpy="0 0 0" />
+      <mass
+        value="8.19341168850207" />
+      <inertia
+        ixx="1.25065484857243"
+        ixy="-0.370837141231599"
+        ixz="-0.214061773475593"
+        iyy="0.581725625286335"
+        iyz="-0.544088624970368"
+        izz="1.03166251957125" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_6.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_6.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_6"
+    type="revolute">
+    <origin
+      xyz="0.037697 -0.0006997 -0.064094"
+      rpy="0.44032 0.19669 -0.83053" />
+    <parent
+      link="Link_5" />
+    <child
+      link="Link_6" />
+    <axis
+      xyz="0.49999 0 -0.86603" />
+    <limit
+      lower="-3.8"
+      upper="3.8"
+      effort="0"
+      velocity="0" />
+  </joint>
+  <link
+    name="Link_7">
+    <inertial>
+      <origin
+        xyz="0.0296425829147993 -6.47728578861279E-06 0.162281442392356"
+        rpy="0 0 0" />
+      <mass
+        value="7.07143232149748" />
+      <inertia
+        ixx="0.0103947066541271"
+        ixy="8.00167786886164E-07"
+        ixz="0.00131122028195651"
+        iyy="0.0112643862205598"
+        iyz="-2.38846633634112E-06"
+        izz="0.0065729384023248" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_7.STL" />
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <mesh
+          filename="package://a9/meshes/Link_7.STL" />
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint_7"
+    type="fixed">
+    <origin
+      xyz="0 0 0"
+      rpy="-2.6972 0.28661 -2.1066" />
+    <parent
+      link="Link_6" />
+    <child
+      link="Link_7" />
+    <axis
+      xyz="0 0 0" />
+  </joint>
+  
+  <link name="end_link_now" />
+  
+  <joint name="end_joint" type="fixed">
+    <parent link="Link_7" />
+    <child link = "end_link_now" />
+    <origin xyz="-0.045 0.0 0.4" rpy="0.0 0.4 3.14" />
+  </joint>
+  
+</robot>

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

@@ -0,0 +1,224 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(lstrobot_planning)
+
+## 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}
+#)

+ 5 - 0
ren_yuan/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
ren_yuan/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
ren_yuan/src/lst_robot_r/msg/JointTrajectory_ex.msg

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

+ 70 - 0
ren_yuan/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>

+ 70 - 0
ren_yuan/src/lst_robot_r/scripts/CloudFunc.py

@@ -0,0 +1,70 @@
+import numpy as np
+import open3d as o3d
+
+
+# 读取文件
+def open_file(file_path):
+    """
+    读取文件
+    :param file_path: 文件路径
+    :return: 读取的内容
+    """
+
+    if '.txt' in file_path:
+        print('txt文档')
+        pcd = o3d.io.read_point_cloud(file_path, format='xyz')
+    else:
+        pcd = o3d.io.read_point_cloud(file_path)
+    return pcd
+
+
+def save_file(content, file_path, write_ascii=True):
+    """
+    保存文件
+    :param write_ascii: 是否使用ASCII编码
+    :param content: 文件内容
+    :param file_path: 保存路径
+    :return: None
+    """
+    if '.txt' in file_path:
+        np.savetxt(file_path, np.asarray(content.points), fmt='%f %f %f')
+    else:
+        o3d.io.write_point_cloud(file_path, content, write_ascii=write_ascii)
+
+
+def voxel_down_sample(pcd, voxel_size):
+    """
+    体素方法点云降采样
+    :param pcd: 点云数据
+    :param voxel_size: 体素降采样的网格长度
+    :return: 降采样点云数据
+    """
+    return pcd.voxel_down_sample(voxel_size=voxel_size)
+
+
+def add_rgb_to_pcd(pcd):
+    """
+    给点云天啊及颜色信息
+    :param pcd: 点云数据
+    :return:
+    """
+    # 为点云中的每个点指定RGB颜色,这里我们使用红色作为示例
+    # RGB值范围为[0, 1],红色可以表示为(1, 0, 0)
+    pcd = np.asarray(pcd.points).shape[0]
+    colors = np.repeat([[1, 0, 0]], pcd, axis=0)  # 创建一个全是红色的颜色数组
+    # 将颜色信息添加到点云对象中
+    pcd.colors = o3d.utility.Vector3dVector(colors)
+    return pcd
+
+
+def pcd_visualization(pcd):
+    """
+    可视化点云数据
+    :param pcd: 点云数据
+    :return: None
+    """
+    o3d.visualization.draw_geometries([pcd],
+                                      zoom=0.3412,
+                                      front=[0.4257, -0.2125, -0.8795],
+                                      lookat=[2.6172, 2.0475, 1.532],
+                                      up=[-0.0694, -0.9768, 0.2024])

+ 145 - 0
ren_yuan/src/lst_robot_r/scripts/check.py

@@ -0,0 +1,145 @@
+import rospy, sys
+import numpy as np
+from tf.transformations import euler_from_quaternion,quaternion_from_euler,quaternion_from_euler, quaternion_multiply
+
+#####检查关节限位#####
+def check_joint_positions(joint_trajectory):
+    is_limited = False      #初始化为满足限制条件
+    Limit_margin = True     #限制边界,初始化为True,用来检查是否超出限制条件
+    
+    for i in range(len(joint_trajectory.joint_trajectory.points) - 1):  #遍历除了最后一个关节轨迹点其他所有轨迹点
+        if  not is_limited:
+            joint_positions1 = joint_trajectory.joint_trajectory.points[i].positions    #选择两个相邻的关节轨迹点
+            joint_positions2 = joint_trajectory.joint_trajectory.points[i + 1].positions 
+
+            for j in range(len(joint_positions1)):    #遍历但前轨迹点的每个关节点,这里是joint_positions1
+                position_diff = abs(joint_positions1[j] - joint_positions2[j])  #计算相邻关节轨迹点的关节点绝对差值,归一化到[-pi,pi]
+                
+                if position_diff > 6:   #限位阈值,6rad=343.8度
+                    rospy.loginfo("发生大角度翻转: point{}-joint{}:{}".format(i,j+1,joint_positions1))
+                    
+                    #关节限位值
+                    joint_limt =[[],[],[],[-1.6,1.6],[],[-3.838,3.838]] 
+                    
+                    #设定限位点为当前关节点
+                    Limit_point = joint_positions1[j]  
+                     
+                    #计算限位点(当前点)与起点位置的偏移量的绝对值
+                    distance_to_Limit_point = abs(joint_trajectory.joint_trajectory.points[0].positions[j]- Limit_point)
+                    Joint_range = abs(joint_limt[j][0] - joint_limt[j][1])  #计算关节限位范围
+                    margin = distance_to_Limit_point / Joint_range          #计算限位余量:偏移量的绝对值/关节限位范围
+                    if margin > 0.3:        
+                        Limit_margin = True  
+                    else:
+                        Limit_margin = False
+                    rospy.loginfo("margin = {}".format(margin))
+                    is_limited = True           
+                    break
+                
+                if position_diff > 3:    #限位阈值,3rad=171.9度
+                    rospy.loginfo("point{}-joint{}:{}".format(i,j+1,joint_positions1))
+      
+                    Limit_margin = True
+                    is_limited = True
+                    break
+        if  is_limited:
+            break
+    if not is_limited:
+        rospy.loginfo("Check OK! 轨迹有效")         
+    return is_limited,Limit_margin
+
+#姿态调整
+def angle_adjustment(pose,axis,angle):      
+    if len(pose) == 6:
+        q_initial = quaternion_from_euler(pose[3], pose[4], pose[5])    #初始姿态四元数,将欧拉角转换为四元数
+    else:
+        q_initial = (pose[3], pose[4], pose[5],pose[6])     #len>6,默认为四元数
+    if axis == 'z':
+        q_rotation = quaternion_from_euler(0, 0, angle)     #绕z轴旋转,转换得到关于z轴的旋转四元数
+    if axis == 'y':
+        q_rotation = quaternion_from_euler(0, angle, 0)
+    if axis == 'x':
+        q_rotation = quaternion_from_euler(angle, 0, 0)    
+    q_new = quaternion_multiply(q_initial, q_rotation)      #q_new为调整后的姿态四元数,值初始姿态四元数乘以旋转四元数
+    pose[3:] = q_new    #将q_new放入pose列表中的3号索引以后的位置
+    return pose
+
+
+
+# def traj_validity_check(trajectory):
+#     if type (trajectory)is moveit_msgs.msg._RobotTrajectory.RobotTrajectory:
+#         point_num=len(trajectory.joint_trajectory.point)
+#         trajectory.joint_trajectory.point.positions
+        
+#         # for i
+#         trajectory.joint_trajectory.point.velocities
+
+#         trajectory.joint_trajectory.point.accelerations
+        
+#         return 0
+#     # else:
+#     #         raise MoveItCommanderException(
+#     #             "Expected value in the range from 0 to 1 for scaling factor"
+#     #         )
+#     def scale_trajectory_speed(traj, scale):
+#        # Create a new trajectory object
+#        new_traj = RobotTrajectory()
+       
+#        # Initialize the new trajectory to be the same as the input trajectory
+#        new_traj.joint_trajectory = traj.joint_trajectory
+       
+#        # Get the number of joints involved
+#        n_joints = len(traj.joint_trajectory.joint_names)
+       
+#        # Get the number of points on the trajectory
+#        n_points = len(traj.joint_trajectory.points)
+        
+#        # Store the trajectory points
+#        points = list(traj.joint_trajectory.points)
+       
+#        # Cycle through all points and joints and scale the time from start,
+#        # as well as joint speed and acceleration
+#        for i in range(n_points):
+#            point = JointTrajectoryPoint()
+           
+#            # The joint positions are not scaled so pull them out first
+#            point.positions = list(traj.joint_trajectory.points[i].positions)
+
+#            # Next, scale the time_from_start for this point
+#             # point.time_from_start = traj.joint_trajectory.points[i].time_from_start / scale
+           
+#            # Get the joint velocities for this point
+#            point.velocities = list(traj.joint_trajectory.points[i].velocities)
+           
+#            # Get the joint accelerations for this point
+#            point.accelerations = list(traj.joint_trajectory.points[i].accelerations)
+           
+#            # Scale the velocity and acceleration for each joint at this point
+#            for j in range(n_joints):
+#             #    if point.positions[j]
+#                if has_velocity_limits:
+#                 if point.velocities[j] > joint_max_velocity[j]:
+#                     vel_exception_point
+#                     rospy.loginfo("velocities Test OK") 
+#                 else:
+#                     raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor")     
+#                if has_acceleration_limits:
+#                 point.accelerations[j] = point.accelerations[j] * scale * scale
+        
+#            # Store the scaled trajectory point
+#            points[i] = point
+
+#        rospy.loginfo("velocities Check OK") 
+
+#        # Assign the modified points to the new trajectory
+#        new_traj.joint_trajectory.points = points
+
+#        # Return the new trajecotry
+#        return new_traj
+
+#     else:
+#         print("traj type is not std")
+    
+
+
+

+ 50 - 0
ren_yuan/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 lstrobot_moveit_config_0605 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)

+ 16 - 0
ren_yuan/src/lst_robot_r/scripts/decorator_time.py

@@ -0,0 +1,16 @@
+#!/usr/bin/env python3
+import rospy
+import time
+
+#定义一个装饰器,用来计算函数运行时间
+#使用方法:在需要计算运行时间的函数前面加上@decorator_time
+
+def decorator_time(func):
+    def wrapper(*args, **kwargs):
+        start_time = time.time()
+        result = func(*args, **kwargs)
+        end_time = time.time()
+        elapsed_time = end_time - start_time
+        rospy.loginfo(f"Time taken by {func.__name__}: {elapsed_time:.4f} seconds")
+        return result
+    return wrapper

+ 162 - 0
ren_yuan/src/lst_robot_r/scripts/dycl_0506.py

@@ -0,0 +1,162 @@
+#!/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 = 4)
+
+################################去掉焊缝周围的点云#################################
+# 计算焊缝向量
+start_points,end_points,vectors = np.array(read_and_calculate_vectors(file_path_points))
+
+data = np.asarray(pcd.points)
+
+
+
+# culling_radius2 = float(rospy.get_param('culling_radius'))
+# data_retained2,data_culled2 =cull_pointcloud(data,culling_radius2)
+# data_scaled2 = np.array(data_retained2) / 1000
+
+
+data_scaled2 = np.array(data) / 1000
+
+
+
+
+
+ptCloud_scaled1 = o3d.geometry.PointCloud()
+
+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)
+
+    
+    points1 = np.asarray(ptCloud_scaled1.points)
+    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()

+ 89 - 0
ren_yuan/src/lst_robot_r/scripts/hanqiangpose.py

@@ -0,0 +1,89 @@
+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,sin,cos
+
+def rpy2quaternion(roll, pitch, yaw):#zyx
+    x=sin(roll/2)*cos(pitch/2)*cos(yaw/2)-cos(roll/2)*sin(pitch/2)*sin(yaw/2)
+    y=cos(roll/2)*sin(pitch/2)*cos(yaw/2)+sin(roll/2)*cos(pitch/2)*sin(yaw/2)
+    z=cos(roll/2)*cos(pitch/2)*sin(yaw/2)-sin(roll/2)*sin(pitch/2)*cos(yaw/2)
+    w=cos(roll/2)*cos(pitch/2)*cos(yaw/2)+sin(roll/2)*sin(pitch/2)*sin(yaw/2)
+    return [x, y, z, w]
+
+
+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 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 run():
+    file_path = rospy.get_param("folder_path")
+    file_path_points = os.path.join(file_path, 'points_guihua.txt')
+    file_path_result = os.path.join(file_path, 'result.txt')
+
+    result=[]
+    start_points, end_points, midpoints, hanfeng = get_hanfeng(file_path_points)
+    # 计算位姿
+    for i in range(len(hanfeng)): 
+        if(calculate_angle_with_xy_plane(start_points[i], end_points[i])<45):#平缝
+            q1 = rpy2quaternion(0,0,np.pi/2)
+            q2 = rpy2quaternion(0,0,np.pi/2)
+            result.append(("s", start_points[i], end_points[i], q1, q2))
+        else:
+            q1 = rpy2quaternion(0,np.pi/2,0)
+            q2 = rpy2quaternion(0,np.pi/2,0)
+            result.append(("s", start_points[i], end_points[i], q1, q2))
+
+
+    # 打开文件准备写入
+    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()

+ 143 - 0
ren_yuan/src/lst_robot_r/scripts/hjsx.py

@@ -0,0 +1,143 @@
+import numpy as np
+import os
+import rospy
+from math import acos, degrees
+def calculate_distance(point1, point2):
+    return np.linalg.norm(np.array(point1) - np.array(point2))
+
+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_points_from_file(file_path):
+    """从文件中读取焊缝数据"""
+    with open(file_path, 'r') as file:
+        lines = file.readlines()
+    data = [line.strip().split('/') for line in lines]
+    points_list = [[tuple(map(float, pair.split(','))) for pair in line] for line in data]
+    return points_list
+########
+# 从文件中读取焊缝起点和终点,并计算两点构成的向量
+def get_hanfeng(file_path):
+
+    data_ping, data_shu = [],[]
+
+    with open(file_path, 'r') as file:
+        # 逐行读取文件内容
+        lines = file.readlines()
+    flag_sequence = 0
+    for line in lines:
+        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) < 30:
+            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
+
+        # 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
+    return data_ping, data_shu, data
+
+
+################################################################################################################
+################################################################################################################
+def sort_welds_by_distance_ping(data_ping, reference_point):
+    """根据与参考点的距离对焊缝进行排序"""
+    sorted_data_ping = []
+    for i in range(len(data_ping)):
+        # 计算起点到参考点的距离并排序
+        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]:
+                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:])
+        reference_point = sorted_data_ping[-1][1]
+        data_ping = [[start, end,flag_sequence] for distances1,distances2, start,end,flag_sequence in data_with_distances]
+    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 run():
+    
+    # 定义参考点
+    reference_point = (1172.85077147, -1.50259925, 668.30298144)
+
+    # file_path = '/home/chen/catkin_ws/src/publish_pointcloud/data/pointclouddata/20240520r'
+    file_path = rospy.get_param("folder_path")
+    file_path_pointcloud = os.path.join(file_path, 'pointcloud.txt')
+    file_path_points = os.path.join(file_path, 'points.txt')
+    file_path_result = os.path.join(file_path, 'result.txt')
+    file_path_points_guihua = os.path.join(file_path, 'points_guihua.txt')
+
+    data_ping, data_shu, data = get_hanfeng(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
+
+    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 __name__ == '__main__':    
+    run()

+ 512 - 0
ren_yuan/src/lst_robot_r/scripts/moveitServer2.py

@@ -0,0 +1,512 @@
+# 导入基本ros和moveit库
+from logging.handlers import RotatingFileHandler
+import os
+import moveit_msgs.msg
+import rospy, sys
+import moveit_commander      
+import moveit_msgs
+
+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
+import tf.transformations
+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 lstrobot_planning.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
+import json
+import termios
+from decorator_time import decorator_time
+import check
+
+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 config
+        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()
+
+    
+    def plan_cartesian_path_LLL(self,point_s,point_e,waypoints,trajectory,trajectory_with_type,a=1,v=1):
+        fraction = 0.0  # 路径规划覆盖率
+        maxtries = 50  # 最大尝试规划次数
+        attempts = 0  # 已经尝试规划次数
+
+        #起点位置设置为规划组最后一个点
+        pose = self.arm.get_current_pose(self.end_effector_link).pose
+        wpose = deepcopy(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))
+        # else:
+        #     wpose.position.x=self.home_pose[0]
+        #     wpose.position.y=self.home_pose[1]
+        #     wpose.position.z=self.home_pose[2]
+        #     wpose.orientation.x=self.home_pose[3]
+        #     wpose.orientation.y=self.home_pose[4]
+        #     wpose.orientation.z=self.home_pose[5]
+        #     wpose.orientation.w=self.home_pose[6]
+        #     waypoint.append(deepcopy(wpose))
+            #waypoints.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 #取出规划的信息
+            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)
+            moveit_server.arm.execute(trajj)
+            trajectory_with_type.append(trajj_with_type)
+        else:
+            rospy.loginfo(
+                "fraction=" + str(fraction) + " success after " + str(maxtries))   
+            
+            # rospy.loginfo("本次焊缝规划失败")
+            # points.pop()#将本条焊缝的起点从规划中删除
+            # trajectory.pop()
+            # trajectory_with_type.pop()
+            # self.hf_fail.append(welding_sequence[self.hf_num])#将焊缝添加到失败列表
+        #self.hf_num=self.hf_num+1#焊缝计数
+        return waypoints,trajectory,trajectory_with_type
+    
+
+    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
+    
+    #TODO move_p_path_constraints    
+    def create_path_constraints2(self,start_point,end_point,r):#创建路径约束
+        #计算起点指向终点的向量
+        vector = np.array([end_point[0]- start_point[0], end_point[1]- start_point[1], end_point[2]- start_point[2]])
+        height = np.linalg.norm(vector)+0.16  #高度延长16cm
+        radius = r
+        
+        # 位置约束
+        position_constraint = PositionConstraint()#创建点位约束
+        position_constraint.header.frame_id = "base_link"#此约束所指的机器人链接
+        position_constraint.link_name = self.end_effector_link
+        position_constraint.target_point_offset = Vector3(0, 0, 0)#目标点的偏移量
+        position_constraint.weight = 1.0#质量 OR 加权因子?
+
+        #构建 shape_msgs/SolidPrimitive 消息
+        bounding_volume = SolidPrimitive()
+        bounding_volume.type = SolidPrimitive.CYLINDER#圆柱
+        # bounding_volume.dimensions = [0.003,1]
+        bounding_volume.dimensions = [height,radius]#尺寸  高度 半径
+        position_constraint.constraint_region.primitives.append(bounding_volume)
+
+        #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
+        pose = Pose()
+        pose.position.x = start_point[0] + vector[0] / 2#定义位置(找了个几何中心)
+        pose.position.y = start_point[1] + vector[1] / 2 
+        pose.position.z = start_point[2] + vector[2] / 2
+        # 计算圆柱体的姿态
+        z_axis = np.array([0, 0, 1])
+        axis = np.cross(z_axis, vector) #计算两个向量(向量数组)的叉乘  叉乘返回的数组既垂直于a,又垂直于b
+        angle = np.arccos(np.dot(z_axis, vector) / np.linalg.norm(vector))#反余弦求角度
+        q = tf.transformations.quaternion_about_axis(angle, axis)#通过旋转轴和旋转角返回四元数
+        pose.orientation.x = q[0]
+        pose.orientation.y = q[1]
+        pose.orientation.z = q[2]
+        pose.orientation.w = q[3]
+        position_constraint.constraint_region.primitive_poses.append(pose)
+
+        constraints = Constraints()#创建一个新的约束信息 
+        constraints.position_constraints.append(position_constraint)
+        # constraints.orientation_constraints.append(orientation_constraint)
+        return constraints
+    
+
+    #TODO move_p_flexible
+    def move_p_flexible(self,point,points,trajectory,trajectory_with_type,a=1,v=1):
+        self.arm.set_max_acceleration_scaling_factor(a)
+        self.arm.set_max_velocity_scaling_factor(v)
+        rrr=0.09#初始允许半径 9cm
+        er=0
+        if trajectory:
+            #起点位置设置为规划组最后一个点
+            state = self.arm.get_current_state()
+            state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
+            path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
+        else:
+            #刚开始规划 起点位置设定为当前状态  按理来说是home点 
+            self.go_home()
+            self.home_pose=self.get_now_pose()
+            state = self.arm.get_current_state()
+            path_constraints = self.create_path_constraints2(self.home_pose,point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
+
+        self.arm.set_path_constraints(path_constraints)#设定约束
+        self.arm.set_pose_target(point, self.end_effector_link)#设定目标点为传入的点
+        self.arm.set_start_state(state)#起点位置设置为规划组最后一个点 或者当前状态(第一个点时)
+        
+        #尝试规划次数
+        b = 4 #尝试规划5次  无约束5次
+        for i in range(b):
+            traj = self.arm.plan()#调用plan进行规划
+            error=traj[3]
+            if  error.val == moveit_msgs.msg._MoveItErrorCodes.MoveItErrorCodes.SUCCESS:
+                trajj = traj[1] #取出规划的信息
+                rospy.loginfo("正在检查移动轨迹有效性...")
+                error_c, limit_margin=check.check_joint_positions(trajj)
+                if not error_c:       
+                    rospy.loginfo("本次移动OK")
+                    rospy.loginfo("*******************")
+                    trajj_with_type = mark_the_traj(trajj,"during-p",welding_sequence)
+                    trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"  
+                    trajj_with_type.points[-1].type = "end"      
+                    trajectory_with_type.append(trajj_with_type)
+                    points.append(point)
+                    trajectory.append(trajj)  
+                    break  
+            else:
+                rospy.loginfo("check failed! 移动轨迹无效")
+                rospy.loginfo("移动规划失败-开始第{}次重新规划".format(i+1))
+                self.arm.clear_path_constraints()
+                rrr=rrr+0.2#每次增加20厘米半径
+                rospy.loginfo("R值:{}".format(rrr))
+                if trajectory:
+                    path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将最后一个点和输入的点(焊缝的起始点)做圆柱轨迹约束
+                else:
+                    path_constraints = self.create_path_constraints2(self.home_pose,point,rrr)#将最后一个点和起点(焊缝的起始点)做圆柱轨迹约束
+                self.arm.set_path_constraints(path_constraints)#设定约束
+                if(i>=(b-2)):
+                    rospy.loginfo("所有移动规划尝试失败 取消路径约束")
+                    self.arm.clear_path_constraints()
+                if(i==(b-1)):
+                    rospy.loginfo("所有移动规划尝试失败  焊缝起点不可达")
+                    er=1
+                    break
+        #清除约束
+        self.arm.clear_path_constraints()
+        
+        return points,trajectory,trajectory_with_type,er
+    
+
+
+
+    #TODO go_home
+    @decorator_time  
+    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 end")
+        self.arm.go()
+        rospy.loginfo("go_home end")
+        # rospy.sleep(1)
+    
+    #TODO go_home_justplan
+    def go_home_justplan(self,trajectory,trajectory_with_type,a=1,v=1):
+        self.arm.set_max_acceleration_scaling_factor(a)
+        self.arm.set_max_velocity_scaling_factor(v)
+        state = self.arm.get_current_state()
+        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]
+        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
+    @decorator_time
+    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]]
+            way_points,trajectory,trajectory_with_type = self.plan_cartesian_path_LLL(point11,point22,way_points,trajectory,trajectory_with_type,v=speed_v)
+
+            rospy.loginfo("第%d条焊缝规划完毕",i+1)
+            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)
+        rospy.loginfo("All of The trajectory Plan successfully")
+        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=[]
+
+def ROS2PY_msgs(msgs, m_sr):
+    for i in range(len(msgs.points)):
+        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()
+
+    # 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}")
+        
+
+            
+
+
+if __name__ =="__main__":
+    # from redis_publisher import Publisher
+    # 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=1
+    # speed_v=get_user_input()
+    # rospy.loginfo(f"用户输入的速度缩放因子为{speed_v}")
+
+    trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning(folder_path)
+    #ROS2_msgs(trajectory_with_type_merge,moveit_server)
+    #write_ee(trajectory_with_type_merge, moveit_server)
+
+
+    # moveit_server.go_home()
+    # moveit_server.arm.execute(trajectory_merge)
+    
+    rospy.set_param("sign_control",0)

+ 48 - 0
ren_yuan/src/lst_robot_r/scripts/redis_publisher.py

@@ -0,0 +1,48 @@
+import time
+import redis
+
+
+class Publisher:
+    def __init__(self):
+        print('redis初始化中..')
+        if not self.redis_init():
+            raise Exception("Redis 初始化失败")
+        self.rds = None
+
+    def redis_init(self, max_retries=5, retry_delay=1):
+        pool = redis.ConnectionPool(host='localhost', port=6379, db=0)
+        retries = 0
+        while retries < max_retries:
+            try:
+                self.rds = redis.Redis(connection_pool=pool)
+                if self.rds.ping():
+                    print("Redis 连接成功.")
+                    return True
+                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 False
+
+    def pub_plan_result(self, result_dict):
+        """
+        发布路径规划结果
+        """
+        if self.rds is not None:
+            self.rds.publish('plan_result', result_dict)
+        else:
+            self.redis_init()
+            self.rds.publish('plan_result', result_dict)
+
+
+if __name__ == '__main__':
+    Publisher()
+

+ 130 - 0
ren_yuan/src/lst_robot_r/scripts/start.py

@@ -0,0 +1,130 @@
+#! /usr/bin/env python3
+import rospy
+import os
+import hanqiangpose
+import command
+import subprocess
+import hjsx
+import threading
+import numpy as np
+import multiprocessing
+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
+
+import actionlib_msgs.msg._GoalStatusArray
+import sys
+import time
+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("set_update_paramter_p")
+
+    # 初始化各种类型参数
+
+    rospy.set_param("cishu",0)
+    rospy.set_param("time",0)
+
+    rospy.set_param("sign_control",1)
+    rospy.set_param("sign_pointcloud",0)
+
+    rospy.set_param("folder_path","/home/robot/ROS/ren_yuan/data/2")
+
+   
+    rospy.loginfo("等待rviz启动")
+    wait_for_topic("/execute_trajectory/status",actionlib_msgs.msg.GoalStatusArray)
+    
+    while not rospy.is_shutdown():
+        sign_control = str(rospy.get_param("sign_control"))
+        if sign_control == "0":
+            if not waited_once:
+                #print("等待点云数据准备完成...")
+                sys.stdin.flush()#清空键盘缓冲区
+                aaa=input("请选择 1-2 默认为2: ")
+                if aaa=="":
+                    aaa='2'
+                #aaa='2'
+
+                rospy.set_param("cishu",rospy.get_param("cishu")+1)
+                if(aaa =='1' or aaa=='2'):
+                    rospy.set_param("sign_control",aaa)
+                else:
+                    command.close_rviz("/usr/bin/python3 /opt/ros/noetic/bin/roslaunch lstrobot_moveit_config_0605 demo.launch")
+                    exit(0)
+                waited_once = True
+        elif sign_control == "1":
+            # 重置参数
+            #rospy.set_param("sign_control",0)    #在轨迹规划里重置 防止重复调用
+            #rospy.set_param("sign_traj_accepted",0)
+            # 清除场景
+            clear_octomap()
+            #点云计算并发布
+            process = multiprocessing.Process(target=command.launch_publish_pointcloud_background)
+            process.start()
+            #计算焊接顺序和焊接姿态
+            hjsx.run()
+            hanqiangpose.run()
+            time.sleep(10)
+            command.load_visual()
+            # 等待 /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)
+            #rospy.loginfo("终止点云发布,关闭发布窗口")
+            
+            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
+ 
+        elif sign_control == "2":
+            tim=time.time()
+            rospy.set_param("time",0)
+            # 重置参数
+            #rospy.set_param("sign_control",0)
+            #rospy.set_param("sign_traj_accepted",0)
+            hjsx.run()
+            hanqiangpose.run()
+            command.load_visual()
+            process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
+            process.start()
+
+            while rospy.get_param("sign_control"):
+                pass
+
+            # tim=time.time()-tim
+            # tim_list.append(tim)
+            # print("-------------------------------------")
+            # print(f'第{rospy.get_param("cishu")}次规划:')
+            # print(tim_list)
+            # print("")
+            
+            #运行结束,重置参数
+            waited_once = False
+
+    
+    

+ 11 - 0
ren_yuan/src/lstrobot_moveit_config_0605/.setup_assistant

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

+ 10 - 0
ren_yuan/src/lstrobot_moveit_config_0605/CMakeLists.txt

@@ -0,0 +1,10 @@
+cmake_minimum_required(VERSION 3.1.3)
+project(lstrobot_moveit_config_0605)
+
+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})

+ 48 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/a9.srdf

@@ -0,0 +1,48 @@
+<?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="a9">
+    <!--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="end_link_now"/>
+    </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="joint_1" value="0"/>
+        <joint name="joint_2" value="0"/>
+        <joint name="joint_3" value="0"/>
+        <joint name="joint_4" value="0"/>
+        <joint name="joint_5" value="0"/>
+        <joint name="joint_6" value="0"/>
+    </group_state>
+    <group_state name="home" group="manipulator">
+        <joint name="joint_1" value="0"/>
+        <joint name="joint_2" value="-1.1311"/>
+        <joint name="joint_3" value="1.459"/>
+        <joint name="joint_4" value="0"/>
+        <joint name="joint_5" value="2.8033"/>
+        <joint name="joint_6" value="2.6393"/>
+    </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="Link_1" link2="Link_2" reason="Adjacent"/>
+    <disable_collisions link1="Link_1" link2="Link_3" reason="Never"/>
+    <disable_collisions link1="Link_1" link2="base_link" reason="Adjacent"/>
+    <disable_collisions link1="Link_2" link2="Link_3" reason="Adjacent"/>
+    <disable_collisions link1="Link_2" link2="Link_5" reason="Never"/>
+    <disable_collisions link1="Link_2" link2="Link_6" reason="Never"/>
+    <disable_collisions link1="Link_3" link2="Link_4" reason="Adjacent"/>
+    <disable_collisions link1="Link_3" link2="Link_5" reason="Never"/>
+    <disable_collisions link1="Link_3" link2="Link_6" reason="Never"/>
+    <disable_collisions link1="Link_3" link2="Link_7" reason="Never"/>
+    <disable_collisions link1="Link_4" link2="Link_5" reason="Adjacent"/>
+    <disable_collisions link1="Link_4" link2="Link_6" reason="Never"/>
+    <disable_collisions link1="Link_5" link2="Link_6" reason="Adjacent"/>
+    <disable_collisions link1="Link_5" link2="Link_7" reason="Never"/>
+    <disable_collisions link1="Link_6" link2="Link_7" reason="Adjacent"/>
+</robot>

+ 5 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/config/fake_controllers.yaml

@@ -0,0 +1,13 @@
+controller_list:
+  - name: fake_manipulator_controller
+    type: $(arg fake_execution_type)
+    joints:
+      - joint_1
+      - joint_2
+      - joint_3
+      - joint_4
+      - joint_5
+      - joint_6
+initial:  # Define initial robot poses per group
+  - group: manipulator
+    pose: zero

+ 296 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/gazebo_a9.urdf

@@ -0,0 +1,296 @@
+<?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="a9">
+    <link name="base_link">
+        <inertial>
+            <origin xyz="-0.110121070288428 -0.0129999995820303 0.159000000973282" rpy="0 0 0" />
+            <mass value="0.0148298653353077" />
+            <inertia ixx="2.02744416702812E-06" ixy="-1.54215522606031E-15" ixz="-3.37592192750916E-14" iyy="1.40267326461625E-06" iyz="-2.76126618174793E-15" izz="1.40267288470545E-06" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/base_link.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/base_link.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <link name="Link_1">
+        <inertial>
+            <origin xyz="0.802922442229256 0.00984539192698494 1.19598646678643" rpy="0 0 0" />
+            <mass value="8.19341168850207" />
+            <inertia ixx="0.19323050511757" ixy="0.0386299594946521" ixz="-0.388616965148905" iyy="1.42567974975729" iyz="0.0128991341474255" izz="1.24513273855516" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_1.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_1.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_1" type="revolute">
+        <origin xyz="0 0 0.278" rpy="0 0 0" />
+        <parent link="base_link" />
+        <child link="Link_1" />
+        <axis xyz="0 0 1" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_2">
+        <inertial>
+            <origin xyz="0.117746157865896 0.0426453911640452 1.20871486266949" rpy="0 0 0" />
+            <mass value="8.19341168850207" />
+            <inertia ixx="0.723493788556202" ixy="0.0285843029943905" ixz="-0.653933580723206" iyy="1.42567974975729" iyz="0.0290103266895879" izz="0.714869455116528" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_2.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_2.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_2" type="revolute">
+        <origin xyz="0.15 -0.0328 0.172" rpy="0 0.47052 0" />
+        <parent link="Link_1" />
+        <child link="Link_2" />
+        <axis xyz="0 1 0" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_3">
+        <inertial>
+            <origin xyz="0.00164806841162357 0.0743961632896021 -0.0125870623969895" rpy="0 0 0" />
+            <mass value="1.10722558532838" />
+            <inertia ixx="0.00281804497282514" ixy="1.0820613146504E-05" ixz="-2.30905562044302E-05" iyy="0.00127732014523064" iyz="5.62797076557556E-06" izz="0.0028367630953507" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_3.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_3.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_3" type="revolute">
+        <origin xyz="-0.59925 0 0.50037" rpy="0 -0.28892 0" />
+        <parent link="Link_2" />
+        <child link="Link_3" />
+        <axis xyz="0 1 0" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_4">
+        <inertial>
+            <origin xyz="0.751501000756241 -0.00505225715113682 0.690060032582326" rpy="0 0 0" />
+            <mass value="8.19341168850207" />
+            <inertia ixx="0.419099372956719" ixy="-0.0348631653478693" ixz="-0.581012917159635" iyy="1.42564974048808" iyz="-0.0218580250133829" izz="1.01929387998522" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_4.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_4.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_4" type="revolute">
+        <origin xyz="-0.084223 0.0347 0.16884" rpy="-3.119 -1.0471 -0.013042" />
+        <parent link="Link_3" />
+        <child link="Link_4" />
+        <axis xyz="0.86603 0 0.5" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_5">
+        <inertial>
+            <origin xyz="0.206551018322306 -0.00505225715114058 -0.104834036546721" rpy="0 0 0" />
+            <mass value="8.19341168850207" />
+            <inertia ixx="0.745717188604768" ixy="0.0281122476978264" ixz="-0.653399595391099" iyy="1.42564974048808" iyz="0.030048545471202" izz="0.69267606433717" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_5.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_5.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_5" type="revolute">
+        <origin xyz="0.92436 0 0.53588" rpy="3.1416 -0.25867 3.1416" />
+        <parent link="Link_4" />
+        <child link="Link_5" />
+        <axis xyz="0 1 0" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_6">
+        <inertial>
+            <origin xyz="0.12280626304832 0.10284172733946 -0.0673247079199191" rpy="0 0 0" />
+            <mass value="8.19341168850207" />
+            <inertia ixx="1.25065484857243" ixy="-0.370837141231599" ixz="-0.214061773475593" iyy="0.581725625286335" iyz="-0.544088624970368" izz="1.03166251957125" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_6.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="1 1 0 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_6.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_6" type="revolute">
+        <origin xyz="0.037697 -0.0006997 -0.064094" rpy="0.44032 0.19669 -0.83053" />
+        <parent link="Link_5" />
+        <child link="Link_6" />
+        <axis xyz="0.49999 0 -0.86603" />
+        <limit lower="-3" upper="3" effort="0" velocity="0" />
+    </joint>
+    <link name="Link_7">
+        <inertial>
+            <origin xyz="0.0296425829147993 -6.47728578861279E-06 0.162281442392356" rpy="0 0 0" />
+            <mass value="7.07143232149748" />
+            <inertia ixx="0.0103947066541271" ixy="8.00167786886164E-07" ixz="0.00131122028195651" iyy="0.0112643862205598" iyz="-2.38846633634112E-06" izz="0.0065729384023248" />
+        </inertial>
+        <visual>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_7.STL" />
+            </geometry>
+            <material name="">
+                <color rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
+            </material>
+        </visual>
+        <collision>
+            <origin xyz="0 0 0" rpy="0 0 0" />
+            <geometry>
+                <mesh filename="package://a9/meshes/Link_7.STL" />
+            </geometry>
+        </collision>
+    </link>
+    <joint name="joint_7" type="fixed">
+        <origin xyz="0 0 0" rpy="-2.6972 0.28661 -2.1066" />
+        <parent link="Link_6" />
+        <child link="Link_7" />
+        <axis xyz="0 0 0" />
+    </joint>
+    <transmission name="trans_joint_1">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_1">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_1_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint_2">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_2">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_2_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint_3">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_3">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_3_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint_4">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_4">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_4_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint_5">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_5">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_5_motor">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+            <mechanicalReduction>1</mechanicalReduction>
+        </actuator>
+    </transmission>
+    <transmission name="trans_joint_6">
+        <type>transmission_interface/SimpleTransmission</type>
+        <joint name="joint_6">
+            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+        </joint>
+        <actuator name="joint_6_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>
+

+ 4 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/gazebo_controllers.yaml

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

+ 40 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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:
+  joint_1:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint_2:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint_3:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint_4:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint_5:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0
+  joint_6:
+    has_velocity_limits: false
+    max_velocity: 0
+    has_acceleration_limits: false
+    max_acceleration: 0

+ 7 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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(joint_1,joint_2)
+  longest_valid_segment_fraction: 0.005

+ 0 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/ros_controllers.yaml


+ 10 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/sensors_3d.yaml

@@ -0,0 +1,10 @@
+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
+

+ 10 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/sensors_3d2.yaml

@@ -0,0 +1,10 @@
+sensors2:
+  - 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/output2
+    point_subsample: 1
+    sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
+

+ 2 - 0
ren_yuan/src/lstrobot_moveit_config_0605/config/simple_moveit_controllers.yaml

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

+ 39 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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

+ 3 - 0
ren_yuan/src/lstrobot_moveit_config_0605/launch/a9_moveit_sensor_manager.launch.xml

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

+ 21 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/chomp_planning.yaml" />
+</launch>

+ 15 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/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
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/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
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/fake_controllers.yaml"/>
+
+</launch>

+ 34 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 joint_1 0 -J joint_2 0 -J joint_3 0 -J joint_4 0 -J joint_5 0 -J joint_6 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 lstrobot_moveit_config_0605)/config/gazebo_a9.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 lstrobot_moveit_config_0605)/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
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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="a9" />
+  </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>

+ 386 - 0
ren_yuan/src/lstrobot_moveit_config_0605/launch/moveit.rviz

@@ -0,0 +1,386 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 84
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /MotionPlanning1/Scene Geometry1
+      Splitter Ratio: 0.5
+    Tree Height: 808
+  - 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: world
+      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
+          Link_1:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_2:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_3:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_4:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_5:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_6:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_7:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          base_link:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          end_link_now:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+          world:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+        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
+          Link_1:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_2:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_3:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_4:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_5:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_6:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          Link_7:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          base_link:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+            Value: true
+          end_link_now:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+          world:
+            Alpha: 1
+            Show Axes: false
+            Show Trail: false
+        Robot Alpha: 0.5
+        Show Robot Collision: false
+        Show Robot Visual: false
+      Value: true
+      Velocity_Scaling_Factor: 0.1
+    - Class: rviz/MarkerArray
+      Enabled: true
+      Marker Topic: rviz_visual_tools
+      Name: MarkerArray
+      Namespaces:
+        Path: true
+        Text: true
+        point0  0.983265  0.126875  0.473115: true
+        point0  0.983765  -0.262875  0.473115: true
+        point1  0.983378  0.122593  0.278064: true
+        point1  0.983994  -0.262691  0.279523: true
+        point2  0.983265  0.126875  0.278115: true
+        point2  1.125382  0.127069  0.280059: true
+        point3  0.983994  -0.261691  0.278523: true
+        point3  1.125382  -0.262691  0.280059: true
+        point4  0.983294  -0.262191  0.463923: true
+        point4  0.984994  -0.263491  0.277923: true
+        point5  0.980265  0.126875  0.278115: true
+        point5  0.983365  0.126875  0.468115: true
+      Queue Size: 100
+      Value: true
+    - 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
+        Link_1:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_2:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_3:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_4:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_5:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_6:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        Link_7:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        base_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        end_link_now:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        world:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+      Name: RobotModel
+      Robot Description: robot_description
+      TF Prefix: ""
+      Update Interval: 0
+      Value: true
+      Visual Enabled: true
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 0.05000000074505806
+      Name: Axes
+      Radius: 0.009999999776482582
+      Reference Frame: end_link_now
+      Show Trail: false
+      Value: true
+    - Class: rviz/TF
+      Enabled: false
+      Filter (blacklist): ""
+      Filter (whitelist): ""
+      Frame Timeout: 15
+      Frames:
+        All Enabled: false
+      Marker Alpha: 1
+      Marker Scale: 1
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        {}
+      Update Interval: 0
+      Value: false
+  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.868440866470337
+      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.43320751190185547
+        Y: 0.5569202899932861
+        Z: -0.5814682245254517
+      Focal Shape Fixed Size: true
+      Focal Shape Size: 0.05000000074505806
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.009999999776482582
+      Pitch: 0.7650017142295837
+      Target Frame: base_link
+      Yaw: 5.316291332244873
+    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: 000000ff00000000fd0000000100000000000001f3000003b9fc0200000007fb000000100044006900730070006c006100790073010000003d000003b9000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006700000001ab000001880000017d00ffffff00000587000003b900000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Views:
+    collapsed: false
+  Width: 1920
+  X: 0
+  Y: 0

+ 15 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/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 lstrobot_moveit_config_0605)/config/chomp_planning.yaml" />
+
+  <!-- override trajectory_initialization_method: Use OMPL-generated trajectory -->
+  <param name="trajectory_initialization_method" value="fillTrajectory"/>
+</launch>

+ 24 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/ompl_planning.yaml"/>
+
+</launch>

+ 15 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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 a9)/urdf/a9.urdf"/>
+
+  <!-- The semantic description that corresponds to the URDF -->
+  <param name="$(arg robot_description)_semantic" textfile="$(find lstrobot_moveit_config_0605)/config/a9.srdf" />
+
+  <!-- Load updated joint limits (override information from URDF) -->
+  <group ns="$(arg robot_description)_planning">
+    <rosparam command="load" file="$(find lstrobot_moveit_config_0605)/config/joint_limits.yaml"/>
+    <rosparam command="load" file="$(find lstrobot_moveit_config_0605)/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 lstrobot_moveit_config_0605)/config/kinematics.yaml"/>
+
+  </group>
+
+</launch>

+ 10 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/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
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/ompl_planning.yaml"/>
+  </node>
+
+</launch>

+ 17 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/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.025" />
+  <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="a9" />
+  <include file="$(dirname)/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" />
+
+</launch>

+ 16 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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=lstrobot_moveit_config_0605"
+        launch-prefix="$(arg launch_prefix)"
+        required="true"
+        output="screen" />
+
+</launch>

+ 8 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/simple_moveit_controllers.yaml" />
+  <rosparam file="$(find lstrobot_moveit_config_0605)/config/ros_controllers.yaml" />
+</launch>

+ 23 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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 lstrobot_moveit_config_0605)/config/stomp_planning.yaml"/>
+</launch>

+ 23 - 0
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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
ren_yuan/src/lstrobot_moveit_config_0605/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>

+ 41 - 0
ren_yuan/src/lstrobot_moveit_config_0605/package.xml

@@ -0,0 +1,41 @@
+<package>
+
+  <name>lstrobot_moveit_config_0605</name>
+  <version>0.3.0</version>
+  <description>
+     An automatically generated package with all the configuration and launch files for using the a9 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>a9</run_depend>
+
+
+</package>

+ 49 - 0
ren_yuan/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
+  lstrobot_moveit_config_0605
+)
+
+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
ren_yuan/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
ren_yuan/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 
+
+*/