bzx 8 tháng trước cách đây
mục cha
commit
da39402942

+ 1 - 0
catkin_ws/src/CMakeLists.txt

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

+ 1 - 1
catkin_ws/src/lstrobot_moveit_config_0605/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml

@@ -7,7 +7,7 @@
   <param name="request_adapters" value="$(arg planning_adapters)" />
 
   <!-- Define default planner (for all groups) -->
-  <param name="default_planner_config" value="PTP" />
+  <param name="default_planner_config" value="RRTConnect" />
 
   <!-- MoveGroup capabilities to load for this pipeline, append sequence capability -->
   <param name="capabilities" value="pilz_industrial_motion_planner/MoveGroupSequenceAction

+ 16 - 17
catkin_ws/src/lstrobot_planning/scripts/moveitServer2.py

@@ -23,7 +23,7 @@ from tf.transformations import euler_from_quaternion,quaternion_from_euler,quate
 import math
 import traceback
 from lstrobot_planning.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
-
+import json
 
 pi = np.pi
 
@@ -436,43 +436,42 @@ class py_msgs():
         xyz_list=[]
         type=[]
 
-def ROS2PY_msgs(msgs,m_sr):
+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()
+    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])
-    print(py_msgs.shun_xv)
-    print(py_msgs.fial)
 
+    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("任意键继续")
 
 if __name__ =="__main__":
+    # from redis_publisher import Publisher
+    # publisher = Publisher()
 
     folder_path = rospy.get_param("folder_path")
-    # 初始化ROS节点
     rospy.init_node('moveit_control_server', anonymous=False)   
     moveit_server = MoveIt_Control(is_use_gripper=False)
     
     welding_sequence = rospy.get_param('welding_sequence')
     trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning(folder_path)
-    # trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning_test(folder_path,1,True)
-    #执行动作
-    
-    #ROS2PY_msgs(trajectory_with_type_merge,moveit_server)
-
-    #moveit_server.arm.execute(trajectory_merge)
     
+    # plan_result = ROS2PY_msgs(trajectory_with_type_merge, moveit_server)
+    # publisher.pub_plan_result(plan_result)
 
-    # for i in range(1 * 2 - 0): #执行到第i条焊缝
-    #     moveit_server.arm.execute(trajectory[i])
+    moveit_server.arm.execute(trajectory_merge)
     
-    #发布规划完毕的轨迹信息
-    #pub_trajectories(trajectory_with_type_merge)
     rospy.set_param("sign_control",0)

+ 48 - 0
catkin_ws/src/lstrobot_planning/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()
+

+ 4 - 4
catkin_ws/src/lstrobot_planning/scripts/set_update_paramter_p.py

@@ -53,7 +53,7 @@ if __name__ == "__main__":
     rospy.set_param("pitch_of_Horizontalweld",np.pi/4)  #和底面夹角(俯仰角)
     rospy.set_param("pitch_of_Verticalweld",np.pi/5)
     rospy.set_param("culling_radius",0) #焊缝剔除半径
-    rospy.set_param("folder_path","/home/robot/ROS/catkin_ws/data/22")
+    rospy.set_param("folder_path","/home/robot/ROS/catkin_ws/data/2")
 
     rospy.loginfo("当前参数值:")# 显示参数当前值
     rospy.loginfo("sign_pointcloud = %s", rospy.get_param("sign_pointcloud"))
@@ -68,9 +68,9 @@ if __name__ == "__main__":
         if sign_control == "0":
             if not waited_once:
                 print("等待点云数据准备完成...")
-                # sys.stdin.flush()#清空键盘缓冲区
-                # aaa=input("请选择 1-2: ")
-                aaa='2'
+                sys.stdin.flush()#清空键盘缓冲区
+                aaa=input("请选择 1-2: ")
+                #aaa='2'
 
                 rospy.set_param("cishu",rospy.get_param("cishu")+1)
                 if(aaa =='1' or aaa=='2'):

+ 2 - 2
catkin_ws/src/mr12urdf20240605/urdf/mr12urdf20240605.urdf

@@ -387,8 +387,8 @@
     <axis
       xyz="0 0 1" />
     <limit
-      lower="-3.838"
-      upper="3.838"
+      lower="-2.1"
+      upper="2.1"
       effort="32.64"
       velocity="23.655" />
   </joint>

+ 2 - 1
catkin_ws/更新记录.txt

@@ -41,5 +41,6 @@
 2024-9-1
 	修复从起点规划到第一个失败后的重新设定约束逻辑问题
 	六轴翻转问题依旧没有解决  其问题会带来运动碰撞风险 不止是极限角度  也是之前轴翻转的根源
-	新隐患:
+2024-9-2
+	通过限制6轴自由度解决六轴翻转问题