moveitServer2.py 21 KB

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