moveitServer2.py 23 KB

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