moveitServer2.py 22 KB

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