moveitServer2.py 23 KB

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