joint2ee.py 2.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #!/usr/bin/env python3
  2. import sys
  3. import moveit_commander
  4. import rospy
  5. """根据轨迹点的六轴角度值,计算末端执行器的位姿"""
  6. """1.roslaunch lstrobot_moveit_config demo.launch"""
  7. """2.rosrun lstrobot_planning joint2ee.py"""
  8. class MoveitPlanner:
  9. def __init__(self, group_name):
  10. # 初始化 moveit_commander
  11. moveit_commander.roscpp_initialize(sys.argv)
  12. rospy.init_node('1111_node', anonymous=True)
  13. self.robot = moveit_commander.RobotCommander()
  14. self.group = moveit_commander.MoveGroupCommander(group_name)
  15. self.planning_scene_interface = moveit_commander.PlanningSceneInterface()
  16. self.end_effector_link = self.group.get_end_effector_link()
  17. def get_robot_state(self):
  18. # 获取当前机械臂状态
  19. return self.robot.get_current_state()
  20. def get_end_effector_pose(self):
  21. # 获取末端执行器的位姿
  22. return self.group.get_current_pose(self.end_effector_link)
  23. #从文件中读取关节角度值
  24. def read_joint_value(input_filename):
  25. joint_value_list = []
  26. with open(input_filename, 'r') as file:
  27. for line in file:
  28. #将每行的关节值转换为浮点数并去掉换行符
  29. joint_value=[float(val) for val in line.strip().split()]
  30. joint_value_list.append(joint_value)
  31. return joint_value_list
  32. #写入末端执行器位姿到目标文件
  33. def write_ee_pose(joint_value_list, planner, output_filename):
  34. with open(output_filename, 'w') as file:
  35. for idx,joint_value in enumerate(joint_value_list):
  36. #设置关节值为当前轨迹点的关节位置
  37. planner.group.set_joint_value_target(joint_value)
  38. plan=planner.group.plan()
  39. if plan:
  40. planner.group.execute(plan[1], wait=True)
  41. fk_result = planner.get_end_effector_pose()
  42. position=fk_result.pose.position
  43. orientation=fk_result.pose.orientation
  44. #格式化位姿数据
  45. pose_data = f"Point {idx + 1}:\n"
  46. pose_data += f"Position: x={position.x}, y={position.y}, z={position.z}\n"
  47. pose_data += f"Orientation (Quaternion): x={orientation.x}, y={orientation.y}, z={orientation.z}, w={orientation.w}\n"
  48. pose_data += "-" * 50 + "\n"
  49. file.write(pose_data)
  50. print(f"End effector pose saved to {output_filename}.")
  51. def main():
  52. planner = MoveitPlanner("manipulator")
  53. input_filename = '/home/tong/moveir_ws/data/123/outtt.txt'
  54. joint_value_list = read_joint_value(input_filename)
  55. output_filename = '/home/tong/moveir_ws/data/123/ee_pose.txt'
  56. write_ee_pose(joint_value_list, planner, output_filename)
  57. if __name__ == '__main__':
  58. main()