lsttry 6 miesięcy temu
rodzic
commit
bdb21653e1

+ 10 - 2
reyuan/lst_robot_r/README.md

@@ -29,7 +29,7 @@
 ## 2024.9.30
 - 添加修改笛卡尔路径参数的函数(速度,加速度)
 - 修正机械臂的初始姿态(home位姿)
-- 修改焊枪位姿,防止规划失败
+- 修改焊接姿态,固定焊接位姿
 
 ## 2024.10.12
 - 增加点云数据,起始点终点数据,测试碰撞检测
@@ -40,4 +40,12 @@
 
 ## 2024.10.29
 - 配置机械臂moveit_config文件
-- 修改模型为fanuc_m10iA/8l
+- 修改仿真模型为fanuc_m10iA/8l
+- 更新2024-9-23-L/try分支代码为最新
+
+## 2024.10.30
+- 待完成:尝试使用plan()代替compute_cartesian_path(),来进行全局避障规划(会出现翻转的情况,应该是初始位姿的问题)
+- 待完成:尝试使用OMPL-CHOMP规划适配器进行规划,即前端使用OMPL获得初始路径,后端使用CHOMP对路径进行优化,提高精度和避障效果
+
+## 2024.10.31(hjsx.py)
+- 修改焊接顺序,使得两条平行焊缝的焊接方向相同

BIN
reyuan/lst_robot_r/scripts/__pycache__/command.cpython-38.pyc


BIN
reyuan/lst_robot_r/scripts/__pycache__/hjsx.cpython-38.pyc


+ 1 - 1
reyuan/lst_robot_r/scripts/command.py

@@ -47,4 +47,4 @@ 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)
+    subprocess.call(command)

+ 6 - 1
reyuan/lst_robot_r/scripts/hjsx.py

@@ -88,6 +88,11 @@ def sort_welds_by_distance_ping(data_ping, reference_point):
         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]
+        
+        #将起始点位置交换回来,保证平缝焊接方向一致
+        for i in range(len(sorted_data_ping)):
+            sorted_data_ping[i][0], sorted_data_ping[i][1] = sorted_data_ping[i][1], sorted_data_ping[i][0]
+            
     return sorted_data_ping
 def sort_welds_by_distance_shu(data_shu, reference_point):
     """根据与参考点的距离对焊缝进行排序"""
@@ -105,7 +110,7 @@ def sort_welds_by_distance_shu(data_shu, reference_point):
     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'

+ 9 - 9
reyuan/lst_robot_r/scripts/moveitServer2.py

@@ -171,24 +171,24 @@ class MoveIt_Control:
         return pose
     
     #TODO move_p_path_constraints    
-    def create_path_constraints(self,start_point,end_point,r):#创建路径约束
+    def create_path_constraints(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
+        height = np.linalg.norm(vector)+0.16  
         radius = r
         
         # 位置约束
-        position_constraint = PositionConstraint()#创建点位约束
-        position_constraint.header.frame_id = "base_link"#此约束所指的机器人链接
+        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 加权因子?
+        position_constraint.target_point_offset = Vector3(0, 0, 0)
+        position_constraint.weight = 1.0
 
         #构建 shape_msgs/SolidPrimitive 消息
         bounding_volume = SolidPrimitive()
         bounding_volume.type = SolidPrimitive.CYLINDER#圆柱
         # bounding_volume.dimensions = [0.003,1]
-        bounding_volume.dimensions = [height,radius]#尺寸  高度 半径
+        bounding_volume.dimensions = [height,radius]
         position_constraint.constraint_region.primitives.append(bounding_volume)
 
         #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
@@ -207,7 +207,7 @@ class MoveIt_Control:
         pose.orientation.w = q[3]
         position_constraint.constraint_region.primitive_poses.append(pose)
 
-        constraints = Constraints()#创建一个新的约束信息 
+        constraints = Constraints()
         constraints.position_constraints.append(position_constraint)
 
         return constraints
@@ -216,7 +216,7 @@ class MoveIt_Control:
     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
+        rrr=0.09    #初始允许半径 9cm
         er=0
         if trajectory:
             #起点位置设置为规划组最后一个点

+ 4 - 3
reyuan/lst_robot_r/scripts/start.py

@@ -36,9 +36,10 @@ def clear_octomap():
 
 waited_once = False
 tim_list=[]
+
 if __name__ == "__main__":
     command.load_rviz()
-    rospy.init_node("set_update_paramter_p")
+    rospy.init_node("start_node")
 
     # 初始化各种类型参数
 
@@ -86,7 +87,7 @@ if __name__ == "__main__":
             #计算焊接顺序和焊接姿态
             hjsx.run()
             hanqiangpose.run()
-            time.sleep(10)
+            #time.sleep(10)
             command.load_visual()
             # 等待 /move_group/monitored_planning_scene 话题发布消息
             rospy.loginfo("等待场景地图加载完毕...")
@@ -130,4 +131,4 @@ if __name__ == "__main__":
             waited_once = False
 
     
-    
+