moveitServer2.py 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459
  1. # 导入基本ros和moveit库
  2. from logging.handlers import RotatingFileHandler
  3. import os
  4. import moveit_msgs.msg
  5. import rospy, sys
  6. import moveit_commander
  7. import moveit_msgs
  8. from moveit_commander import MoveGroupCommander, PlanningSceneInterface, RobotCommander
  9. from moveit_msgs.msg import PlanningScene, ObjectColor,CollisionObject, AttachedCollisionObject,RobotTrajectory
  10. from moveit_msgs.msg import RobotState
  11. from moveit_msgs.msg import Constraints, PositionConstraint, OrientationConstraint
  12. from shape_msgs.msg import SolidPrimitive
  13. from sensor_msgs.msg import JointState
  14. import tf.transformations
  15. from trajectory_msgs.msg import JointTrajectory,JointTrajectoryPoint
  16. from geometry_msgs.msg import PoseStamped, Pose,Point,Vector3
  17. from copy import deepcopy
  18. import numpy as np
  19. import tf
  20. from tf.transformations import euler_from_quaternion,quaternion_from_euler,quaternion_from_euler, quaternion_multiply
  21. import math
  22. import traceback
  23. from lstrobot_planning.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
  24. pi = np.pi
  25. class MoveIt_Control:
  26. # 初始化程序
  27. def __init__(self, is_use_gripper=False):
  28. self.home_pose=[]
  29. self.hf_num=0#焊缝计数 从0开始
  30. self.hf_fail=[]
  31. # Init ros config
  32. moveit_commander.roscpp_initialize(sys.argv)
  33. self.arm = moveit_commander.MoveGroupCommander('manipulator')
  34. self.arm.set_goal_joint_tolerance(0.0001)
  35. self.arm.set_goal_position_tolerance(0.0005)
  36. self.arm.set_goal_orientation_tolerance(0.1)
  37. self.end_effector_link = self.arm.get_end_effector_link()
  38. # 设置机械臂基座的参考系
  39. self.reference_frame = 'base_link'
  40. self.arm.set_pose_reference_frame(self.reference_frame)
  41. # # 设置最大规划时间和是否允许重新规划
  42. self.arm.set_planning_time(10)
  43. self.arm.allow_replanning(True)
  44. self.arm.set_max_acceleration_scaling_factor(1)
  45. self.arm.set_max_velocity_scaling_factor(1)
  46. self.arm.set_num_planning_attempts(10)
  47. # 机械臂初始姿态
  48. self.go_home()
  49. self.home_pose=self.get_now_pose()
  50. def get_now_pose(self):
  51. # 获取机械臂当前位姿
  52. current_pose = self.arm.get_current_pose(self.end_effector_link).pose
  53. pose=[]
  54. pose.append(current_pose.position.x)
  55. pose.append(current_pose.position.y)
  56. pose.append(current_pose.position.z)
  57. pose.append(current_pose.orientation.x)
  58. pose.append(current_pose.orientation.y)
  59. pose.append(current_pose.orientation.z)
  60. pose.append(current_pose.orientation.w)
  61. # 打印位姿信息
  62. #rospy.lohome_poseinfo("Current Pose: {}".format(pose))
  63. return pose
  64. def create_path_constraints2(self,start_point,end_point,r):#创建路径约束
  65. #计算起点指向终点的向量
  66. vector = np.array([end_point[0]- start_point[0], end_point[1]- start_point[1], end_point[2]- start_point[2]])
  67. height = np.linalg.norm(vector)+0.006 #计算向量或矩阵的范数 用于度量向量或矩阵的大小或长度
  68. radius = r
  69. # 位置约束
  70. position_constraint = PositionConstraint()#创建点位约束
  71. position_constraint.header.frame_id = "base_link"#此约束所指的机器人链接
  72. position_constraint.link_name = self.end_effector_link
  73. position_constraint.target_point_offset = Vector3(0, 0, 0)#目标点的偏移量
  74. position_constraint.weight = 1.0#质量 OR 加权因子?
  75. #构建 shape_msgs/SolidPrimitive 消息
  76. bounding_volume = SolidPrimitive()
  77. bounding_volume.type = SolidPrimitive.CYLINDER#圆柱
  78. # bounding_volume.dimensions = [0.003,1]
  79. bounding_volume.dimensions = [height,radius]#尺寸 高度 半径
  80. position_constraint.constraint_region.primitives.append(bounding_volume)
  81. #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
  82. pose = Pose()
  83. pose.position.x = start_point[0] + vector[0] / 2#定义位置(找了个几何中心)
  84. pose.position.y = start_point[1] + vector[1] / 2
  85. pose.position.z = start_point[2] + vector[2] / 2
  86. # 计算圆柱体的姿态
  87. z_axis = np.array([0, 0, 1])
  88. axis = np.cross(z_axis, vector) #计算两个向量(向量数组)的叉乘 叉乘返回的数组既垂直于a,又垂直于b
  89. angle = np.arccos(np.dot(z_axis, vector) / np.linalg.norm(vector))#反余弦求角度
  90. q = tf.transformations.quaternion_about_axis(angle, axis)#通过旋转轴和旋转角返回四元数
  91. pose.orientation.x = q[0]
  92. pose.orientation.y = q[1]
  93. pose.orientation.z = q[2]
  94. pose.orientation.w = q[3]
  95. position_constraint.constraint_region.primitive_poses.append(pose)
  96. constraints = Constraints()#创建一个新的约束信息
  97. constraints.position_constraints.append(position_constraint)
  98. # constraints.orientation_constraints.append(orientation_constraint)
  99. return constraints
  100. def move_p_flexible(self,point,points,trajectory,trajectory_with_type,a=1,v=1):
  101. self.arm.set_max_acceleration_scaling_factor(a)
  102. self.arm.set_max_velocity_scaling_factor(v)
  103. rrr=0.05#初始允许半径
  104. if trajectory:
  105. #起点位置设置为规划组最后一个点
  106. state = self.arm.get_current_state()
  107. state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
  108. path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
  109. else:
  110. #刚开始规划 起点位置设定为当前状态 按理来说是home点
  111. self.go_home()
  112. self.home_pose=self.get_now_pose()
  113. state = self.arm.get_current_state()
  114. path_constraints = self.create_path_constraints2(self.home_pose,point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
  115. self.arm.set_path_constraints(path_constraints)#设定约束
  116. self.arm.set_pose_target(point, self.end_effector_link)#设定目标点为传入的点
  117. self.arm.set_start_state(state)#起点位置设置为规划组最后一个点 或者当前状态(第一个点时)
  118. #尝试规划次数
  119. b = 16 #尝试规划10次
  120. for i in range(b):
  121. traj = self.arm.plan()#调用plan进行规划
  122. error=traj[3]
  123. if error.val == moveit_msgs.msg._MoveItErrorCodes.MoveItErrorCodes.SUCCESS:
  124. rospy.loginfo("本次移动OK")
  125. trajj = traj[1] #取出规划的信息
  126. trajj_with_type = mark_the_traj(trajj,"during-p",welding_sequence)
  127. trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
  128. trajj_with_type.points[-1].type = "end"
  129. trajectory_with_type.append(trajj_with_type)
  130. points.append(point)
  131. trajectory.append(trajj)
  132. break
  133. else:
  134. rospy.loginfo("移动规划失败-开始第{}次重新规划".format(i+1))
  135. self.arm.clear_path_constraints()
  136. rrr=rrr+0.2#每次增加10厘米
  137. rospy.loginfo("R值:{}次重新规划".format(rrr))
  138. path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将最后一个点和输入的点(焊缝的起始点)做圆柱轨迹约束
  139. self.arm.set_path_constraints(path_constraints)#设定约束
  140. if(i==(b-1)):
  141. rospy.loginfo("所有移动规划尝试失败 规划器停止---请检查工件")
  142. self.arm.clear_path_constraints()
  143. sys.exit(0)
  144. #清除约束
  145. self.arm.clear_path_constraints()
  146. return points,trajectory,trajectory_with_type
  147. def move_pl(self,point,points,trajectory,trajectory_with_type,a=1,v=1):#焊缝的规划 只规划当前的点到上一个点
  148. self.arm.set_max_acceleration_scaling_factor(a)
  149. self.arm.set_max_velocity_scaling_factor(v)
  150. #设定约束
  151. if trajectory:
  152. #起点位置设置为规划组最后一个点
  153. state = self.arm.get_current_state()
  154. state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
  155. self.arm.set_start_state(state)
  156. self.arm.set_pose_target(point, self.end_effector_link)#设定目标点为传入的点
  157. # 创建路径约束
  158. path_constraints = self.create_path_constraints(points[-1],point)#将最后一个点和输入的点(焊缝的起始点)做圆柱轨迹约束
  159. self.arm.set_path_constraints(path_constraints)#设定约束
  160. traj = self.arm.plan()#调用plan进行规划
  161. error=traj[3]
  162. if error.val == moveit_msgs.msg._MoveItErrorCodes.MoveItErrorCodes.SUCCESS:
  163. rospy.loginfo("本次焊缝规划 OK")
  164. trajj = traj[1] #取出规划的信息
  165. trajj_with_type = mark_the_traj(trajj,"during-l",welding_sequence)
  166. trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
  167. trajj_with_type.points[-1].type = "end"
  168. points.append(point)
  169. trajectory.append(trajj)
  170. trajectory_with_type.append(trajj_with_type)
  171. else:
  172. rospy.loginfo("本次焊缝规划失败")
  173. points.pop()#将本条焊缝的起点从规划中删除
  174. trajectory.pop()
  175. trajectory_with_type.pop()
  176. self.hf_fail.append(welding_sequence[self.hf_num])
  177. #清除约束
  178. self.arm.clear_path_constraints()
  179. self.hf_num=self.hf_num+1#焊缝计数
  180. return points,trajectory,trajectory_with_type
  181. def create_path_constraints(self,start_point,end_point):
  182. #计算起点指向终点的向量
  183. vector = np.array([end_point[0]- start_point[0], end_point[1]- start_point[1], end_point[2]- start_point[2]])
  184. height = np.linalg.norm(vector)+0.002
  185. radius = 0.001
  186. constraints = Constraints()
  187. # 位置约束
  188. position_constraint = PositionConstraint()
  189. position_constraint.header.frame_id = "base_link"
  190. position_constraint.link_name = self.end_effector_link
  191. position_constraint.target_point_offset = Vector3(0, 0, 0)
  192. #构建 shape_msgs/SolidPrimitive 消息
  193. bounding_volume = SolidPrimitive()
  194. bounding_volume.type = SolidPrimitive.CYLINDER
  195. # bounding_volume.dimensions = [0.003,1]
  196. bounding_volume.dimensions = [height,radius]
  197. #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
  198. pose = Pose()
  199. pose.position.x = start_point[0] + vector[0] / 2
  200. pose.position.y = start_point[1] + vector[1] / 2
  201. pose.position.z = start_point[2] + vector[2] / 2
  202. # 计算圆柱体的旋转矩阵
  203. z_axis = np.array([0, 0, 1])
  204. axis = np.cross(z_axis, vector)
  205. angle = np.arccos(np.dot(z_axis, vector) / np.linalg.norm(vector))
  206. q = tf.transformations.quaternion_about_axis(angle, axis)
  207. pose.orientation.x = q[0]
  208. pose.orientation.y = q[1]
  209. pose.orientation.z = q[2]
  210. pose.orientation.w = q[3]
  211. position_constraint.constraint_region.primitives.append(bounding_volume)
  212. position_constraint.constraint_region.primitive_poses.append(pose)
  213. position_constraint.weight = 1.0
  214. constraints.position_constraints.append(position_constraint)
  215. return constraints
  216. def go_home(self,a=1,v=1):
  217. rospy.loginfo("go_home start")
  218. self.arm.set_max_acceleration_scaling_factor(a)
  219. self.arm.set_max_velocity_scaling_factor(v)
  220. # “up”为自定义姿态,你可以使用“home”或者其他姿态
  221. self.arm.set_named_target('home')
  222. rospy.loginfo("get_home end")
  223. self.arm.go()
  224. rospy.loginfo("go_home end")
  225. # rospy.sleep(1)
  226. def go_home_justplan(self,trajectory,trajectory_with_type,a=1,v=1):
  227. self.arm.set_max_acceleration_scaling_factor(a)
  228. self.arm.set_max_velocity_scaling_factor(v)
  229. # “up”为自定义姿态,你可以使用“home”或者其他姿态
  230. state = self.arm.get_current_state()
  231. state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
  232. self.arm.set_start_state(state)
  233. self.arm.set_named_target('home')
  234. traj = self.arm.plan()
  235. trajj = traj[1]
  236. traj_with_type = mark_the_traj(trajj,"go-home",welding_sequence)
  237. trajectory.append(trajj)
  238. trajectory_with_type.append(traj_with_type)
  239. return trajectory,trajectory_with_type
  240. def path_planning(self,folder_path,gohome=True):
  241. file_path_result = os.path.join(folder_path, 'result.txt')
  242. all_data = process_welding_data(file_path_result)
  243. points,trajectory,trajectory_with_type = [],[],[]
  244. for i in range(len(all_data)):
  245. rospy.loginfo("共读取到%d条焊缝,开始规划第%d条",len(all_data),i+1)
  246. start_point = all_data[i][0]
  247. end_point = all_data[i][1]
  248. q1 = all_data[i][2]
  249. q2 = all_data[i][3]
  250. point11 = [start_point[0]/1000, start_point[1]/1000, start_point[2]/1000, q1[0],q1[1],q1[2],q1[3]]
  251. points,trajectory,trajectory_with_type = self.move_p_flexible(point11,points,trajectory,trajectory_with_type)
  252. point22 = [end_point[0]/1000, end_point[1]/1000, end_point[2]/1000, q2[0],q2[1],q2[2],q2[3]]
  253. points,trajectory,trajectory_with_type = self.move_pl(point22,points,trajectory,trajectory_with_type)
  254. rospy.loginfo("第%d条焊缝规划完毕",i+1)
  255. if gohome:
  256. points,trajectory,trajectory_with_type = self.move_p_flexible(self.home_pose,points,trajectory,trajectory_with_type)
  257. trajectory,trajectory_with_type = self.go_home_justplan(trajectory,trajectory_with_type)
  258. traj_merge= merge_trajectories(trajectory)
  259. trajectory_with_type_merge= merge_trajectories_with_type(trajectory_with_type)
  260. rospy.loginfo("All of The trajectory Plan successfully")
  261. return trajectory,traj_merge,trajectory_with_type_merge
  262. ###########################################################class end#############################################################
  263. def process_welding_data(filename):
  264. all_data = [] # 用来存储每一行处理后的数据
  265. with open(filename, 'r') as file:
  266. for line in file:
  267. parts = line.strip().split('/')
  268. coordinates_and_poses = [part.split(',') for part in parts[1:]]
  269. start_point = tuple(map(float, coordinates_and_poses[0][:3])) # 使用元组以避免修改
  270. end_point = tuple(map(float, coordinates_and_poses[1][:3]))
  271. q1 = tuple(map(float, coordinates_and_poses[2][:4]))
  272. q2 = tuple(map(float, coordinates_and_poses[3][:4]))
  273. # 收集每行处理后的数据
  274. all_data.append((start_point, end_point, q1, q2))
  275. return all_data
  276. def mark_the_traj(traj,TYPE,SEQUENCE):
  277. traj_with_type = JointTrajectory_ex()
  278. traj_with_type.header = traj.joint_trajectory.header
  279. traj_with_type.joint_names = traj.joint_trajectory.joint_names
  280. traj_with_type.points = [
  281. JointTrajectoryPoint_ex(
  282. positions=point.positions,
  283. velocities=point.velocities,
  284. accelerations=point.accelerations,
  285. effort=point.effort,
  286. type=TYPE,
  287. sequence=SEQUENCE
  288. ) for point in traj.joint_trajectory.points
  289. ]
  290. return traj_with_type
  291. def merge_trajectories(trajectories):
  292. if not trajectories:
  293. return None
  294. # 创建一个新的 JointTrajectory 对象
  295. merged_trajectory = JointTrajectory()
  296. merged_trajectory.header = trajectories[0].joint_trajectory.header
  297. merged_trajectory.joint_names = trajectories[0].joint_trajectory.joint_names
  298. # 初始化时间累加器
  299. last_time_from_start = rospy.Duration(0)
  300. # 合并所有 trajectories 的 points
  301. for traj in trajectories:
  302. for point in traj.joint_trajectory.points:
  303. # 创建新的轨迹点
  304. new_point = deepcopy(point)
  305. # 累加时间
  306. new_point.time_from_start += last_time_from_start
  307. merged_trajectory.points.append(new_point)
  308. # 更新时间累加器为当前轨迹的最后一个点的时间
  309. if traj.joint_trajectory.points:
  310. last_time_from_start = traj.joint_trajectory.points[-1].time_from_start + last_time_from_start
  311. return merged_trajectory
  312. def merge_trajectories_with_type(trajectory_with_type):
  313. if not trajectory_with_type:
  314. return None
  315. # 创建一个新的 JointTrajectory 对象
  316. merged_trajectory_with_type = JointTrajectory_ex()
  317. merged_trajectory_with_type.header = trajectory_with_type[0].header
  318. merged_trajectory_with_type.joint_names = trajectory_with_type[0].joint_names
  319. # 初始化时间累加器
  320. last_time_from_start = rospy.Duration(0)
  321. # 合并所有 trajectories 的 points
  322. for traj in trajectory_with_type:
  323. for point in traj.points:
  324. # 创建新的轨迹点
  325. new_point = deepcopy(point)
  326. # 累加时间
  327. new_point.time_from_start += last_time_from_start
  328. merged_trajectory_with_type.points.append(new_point)
  329. # 更新时间累加器为当前轨迹的最后一个点的时间
  330. if traj.points:
  331. last_time_from_start = traj.points[-1].time_from_start + last_time_from_start
  332. return merged_trajectory_with_type
  333. def pub_trajectories(trajectory_with_type_merge):
  334. pub = rospy.Publisher("/joint_path", JointTrajectory_ex, queue_size=5)
  335. count = 1
  336. rate = rospy.Rate(1)
  337. rospy.loginfo("正在发布轨迹信息..")
  338. while not rospy.is_shutdown():
  339. #轨迹接受完毕,关闭当前发布
  340. sign_traj_accepted = str(rospy.get_param("sign_traj_accepted"))
  341. if sign_traj_accepted == "1":
  342. rospy.set_param("sign_traj_accepted",0)
  343. break
  344. pub.publish(trajectory_with_type_merge)
  345. # rospy.loginfo("发布计数,count = %d",count)
  346. # count += 1
  347. rate.sleep()
  348. class py_msgs():
  349. fial=[]
  350. shun_xv=[]
  351. class point():
  352. xyz_list=[]
  353. type=[]
  354. def ROS2PY_msgs(msgs,m_sr):
  355. for i in range(len(msgs.points)):
  356. py_msgs.point.xyz_list.append(msgs.points[i].positions)
  357. py_msgs.point.type.append(msgs.points[i].type)
  358. py_msgs.fail=m_sr.hf_fail.copy()
  359. py_msgs.shun_xv=msgs.points[0].sequence.copy()
  360. for i in range(len(py_msgs.point.type)):
  361. print(py_msgs.point.xyz_list[i])
  362. print(py_msgs.point.type[i])
  363. print(py_msgs.shun_xv)
  364. print(py_msgs.fial)
  365. if __name__ =="__main__":
  366. folder_path = rospy.get_param("folder_path")
  367. # 初始化ROS节点
  368. rospy.init_node('moveit_control_server', anonymous=False)
  369. moveit_server = MoveIt_Control(is_use_gripper=False)
  370. welding_sequence = rospy.get_param('welding_sequence')
  371. trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning(folder_path)
  372. # trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning_test(folder_path,1,True)
  373. #执行动作
  374. ROS2PY_msgs(trajectory_with_type_merge,moveit_server)
  375. moveit_server.arm.execute(trajectory_merge)
  376. # for i in range(1 * 2 - 0): #执行到第i条焊缝
  377. # moveit_server.arm.execute(trajectory[i])
  378. #发布规划完毕的轨迹信息
  379. #pub_trajectories(trajectory_with_type_merge)