moveitServer2.py 27 KB

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