|
@@ -25,8 +25,7 @@ import traceback
|
|
from lst_robot_r.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
|
|
from lst_robot_r.msg import JointTrajectoryPoint_ex,JointTrajectory_ex
|
|
import json
|
|
import json
|
|
import termios
|
|
import termios
|
|
-from decorator_time import decorator_time
|
|
|
|
-import check
|
|
|
|
|
|
+
|
|
|
|
|
|
pi = np.pi
|
|
pi = np.pi
|
|
|
|
|
|
@@ -36,7 +35,7 @@ class MoveIt_Control:
|
|
self.home_pose=[]
|
|
self.home_pose=[]
|
|
self.hf_num=0#焊缝计数 从0开始
|
|
self.hf_num=0#焊缝计数 从0开始
|
|
self.hf_fail=[]
|
|
self.hf_fail=[]
|
|
- # Init ros config
|
|
|
|
|
|
+ # Init ros configs
|
|
moveit_commander.roscpp_initialize(sys.argv)
|
|
moveit_commander.roscpp_initialize(sys.argv)
|
|
self.robot = moveit_commander.RobotCommander()
|
|
self.robot = moveit_commander.RobotCommander()
|
|
|
|
|
|
@@ -65,8 +64,9 @@ class MoveIt_Control:
|
|
self.home_pose=self.get_now_pose()
|
|
self.home_pose=self.get_now_pose()
|
|
#self.go_ready()
|
|
#self.go_ready()
|
|
|
|
|
|
|
|
+
|
|
#TODO plan_cartesian_path
|
|
#TODO plan_cartesian_path
|
|
- def plan_cartesian_path_LLL(self,point_s,point_e,waypoints,trajectory,trajectory_with_type,a=1,v=1):
|
|
|
|
|
|
+ def plan_cartesian_path_LLL(self,point_s,point_e,waypoints,trajectory,trajectory_with_type,v=1):
|
|
fraction = 0.0 # 路径规划覆盖率
|
|
fraction = 0.0 # 路径规划覆盖率
|
|
maxtries = 50 # 最大尝试规划次数
|
|
maxtries = 50 # 最大尝试规划次数
|
|
attempts = 0 # 已经尝试规划次数
|
|
attempts = 0 # 已经尝试规划次数
|
|
@@ -112,15 +112,15 @@ class MoveIt_Control:
|
|
(plan, fraction) = self.arm.compute_cartesian_path(
|
|
(plan, fraction) = self.arm.compute_cartesian_path(
|
|
waypoint, # waypoint poses,路点列表
|
|
waypoint, # waypoint poses,路点列表
|
|
0.001, # eef_step,终端步进值
|
|
0.001, # eef_step,终端步进值
|
|
- 0.0, # jump_threshold,跳跃阈值
|
|
|
|
- True) # avoid_collisions,避障规划
|
|
|
|
|
|
+ 0.0, # jump_threshold,跳跃阈值
|
|
|
|
+ True) # avoid_collisions,避障规划
|
|
attempts += 1
|
|
attempts += 1
|
|
|
|
|
|
if fraction == 1.0 :
|
|
if fraction == 1.0 :
|
|
rospy.loginfo("Path computed successfully.")
|
|
rospy.loginfo("Path computed successfully.")
|
|
#traj = plan
|
|
#traj = plan
|
|
trajj = plan #取出规划的信息
|
|
trajj = plan #取出规划的信息
|
|
- retimed_planed=self.retime_plan(trajj)
|
|
|
|
|
|
+ retimed_planed=self.retime_plan(trajj,v)
|
|
trajj_with_type = mark_the_traj(trajj,"during-l",welding_sequence)
|
|
trajj_with_type = mark_the_traj(trajj,"during-l",welding_sequence)
|
|
trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
|
|
trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
|
|
trajj_with_type.points[-1].type = "end"
|
|
trajj_with_type.points[-1].type = "end"
|
|
@@ -130,8 +130,7 @@ class MoveIt_Control:
|
|
rospy.loginfo("执行结束")
|
|
rospy.loginfo("执行结束")
|
|
trajectory_with_type.append(trajj_with_type)
|
|
trajectory_with_type.append(trajj_with_type)
|
|
else:
|
|
else:
|
|
- rospy.loginfo(
|
|
|
|
- "fraction=" + str(fraction) + " success after " + str(maxtries))
|
|
|
|
|
|
+ rospy.loginfo("fraction=" + str(fraction) + " success after " + str(maxtries))
|
|
|
|
|
|
# rospy.loginfo("本次焊缝规划失败")
|
|
# rospy.loginfo("本次焊缝规划失败")
|
|
# points.pop()#将本条焊缝的起点从规划中删除
|
|
# points.pop()#将本条焊缝的起点从规划中删除
|
|
@@ -141,17 +140,17 @@ class MoveIt_Control:
|
|
#self.hf_num=self.hf_num+1#焊缝计数
|
|
#self.hf_num=self.hf_num+1#焊缝计数
|
|
return waypoints,trajectory,trajectory_with_type
|
|
return waypoints,trajectory,trajectory_with_type
|
|
|
|
|
|
- def retime_plan(self,traj):
|
|
|
|
|
|
+ #TODO retime_plan
|
|
|
|
+ def retime_plan(self,traj,v):
|
|
current_state = self.arm.get_current_state()
|
|
current_state = self.arm.get_current_state()
|
|
|
|
|
|
retimed_traj = self.arm.retime_trajectory(
|
|
retimed_traj = self.arm.retime_trajectory(
|
|
current_state,
|
|
current_state,
|
|
traj,
|
|
traj,
|
|
- velocity_scaling_factor=0.5,
|
|
|
|
|
|
+ velocity_scaling_factor=0.03,
|
|
acceleration_scaling_factor=1)
|
|
acceleration_scaling_factor=1)
|
|
|
|
|
|
return retimed_traj
|
|
return retimed_traj
|
|
-
|
|
|
|
|
|
|
|
def get_now_pose(self):
|
|
def get_now_pose(self):
|
|
# 获取机械臂当前位姿
|
|
# 获取机械臂当前位姿
|
|
@@ -169,116 +168,116 @@ class MoveIt_Control:
|
|
#rospy.lohome_poseinfo("Current Pose: {}".format(pose))
|
|
#rospy.lohome_poseinfo("Current Pose: {}".format(pose))
|
|
return pose
|
|
return pose
|
|
|
|
|
|
- #TODO move_p_path_constraints
|
|
|
|
- def create_path_constraints2(self,start_point,end_point,r):#创建路径约束
|
|
|
|
- #计算起点指向终点的向量
|
|
|
|
- vector = np.array([end_point[0]- start_point[0], end_point[1]- start_point[1], end_point[2]- start_point[2]])
|
|
|
|
- height = np.linalg.norm(vector)+0.16 #高度延长16cm
|
|
|
|
- radius = r
|
|
|
|
|
|
+ def zhu_shi():#折叠注释代码用的
|
|
|
|
|
|
- # 位置约束
|
|
|
|
- position_constraint = PositionConstraint()#创建点位约束
|
|
|
|
- position_constraint.header.frame_id = "base_link"#此约束所指的机器人链接
|
|
|
|
- position_constraint.link_name = self.end_effector_link
|
|
|
|
- position_constraint.target_point_offset = Vector3(0, 0, 0)#目标点的偏移量
|
|
|
|
- position_constraint.weight = 1.0#质量 OR 加权因子?
|
|
|
|
-
|
|
|
|
- #构建 shape_msgs/SolidPrimitive 消息
|
|
|
|
- bounding_volume = SolidPrimitive()
|
|
|
|
- bounding_volume.type = SolidPrimitive.CYLINDER#圆柱
|
|
|
|
- # bounding_volume.dimensions = [0.003,1]
|
|
|
|
- bounding_volume.dimensions = [height,radius]#尺寸 高度 半径
|
|
|
|
- position_constraint.constraint_region.primitives.append(bounding_volume)
|
|
|
|
-
|
|
|
|
- #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
|
|
|
|
- pose = Pose()
|
|
|
|
- pose.position.x = start_point[0] + vector[0] / 2#定义位置(找了个几何中心)
|
|
|
|
- pose.position.y = start_point[1] + vector[1] / 2
|
|
|
|
- pose.position.z = start_point[2] + vector[2] / 2
|
|
|
|
- # 计算圆柱体的姿态
|
|
|
|
- z_axis = np.array([0, 0, 1])
|
|
|
|
- axis = np.cross(z_axis, vector) #计算两个向量(向量数组)的叉乘 叉乘返回的数组既垂直于a,又垂直于b
|
|
|
|
- angle = np.arccos(np.dot(z_axis, vector) / np.linalg.norm(vector))#反余弦求角度
|
|
|
|
- q = tf.transformations.quaternion_about_axis(angle, axis)#通过旋转轴和旋转角返回四元数
|
|
|
|
- pose.orientation.x = q[0]
|
|
|
|
- pose.orientation.y = q[1]
|
|
|
|
- pose.orientation.z = q[2]
|
|
|
|
- pose.orientation.w = q[3]
|
|
|
|
- position_constraint.constraint_region.primitive_poses.append(pose)
|
|
|
|
-
|
|
|
|
- constraints = Constraints()#创建一个新的约束信息
|
|
|
|
- constraints.position_constraints.append(position_constraint)
|
|
|
|
- # constraints.orientation_constraints.append(orientation_constraint)
|
|
|
|
- return constraints
|
|
|
|
-
|
|
|
|
-
|
|
|
|
- #TODO move_p_flexible
|
|
|
|
- def move_p_flexible(self,point,points,trajectory,trajectory_with_type,a=1,v=1):
|
|
|
|
- self.arm.set_max_acceleration_scaling_factor(a)
|
|
|
|
- self.arm.set_max_velocity_scaling_factor(v)
|
|
|
|
- rrr=0.09#初始允许半径 9cm
|
|
|
|
- er=0
|
|
|
|
- if trajectory:
|
|
|
|
- #起点位置设置为规划组最后一个点
|
|
|
|
- state = self.arm.get_current_state()
|
|
|
|
- state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
|
|
|
|
- path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
- else:
|
|
|
|
- #刚开始规划 起点位置设定为当前状态 按理来说是home点
|
|
|
|
- self.go_home()
|
|
|
|
- self.home_pose=self.get_now_pose()
|
|
|
|
- state = self.arm.get_current_state()
|
|
|
|
- path_constraints = self.create_path_constraints2(self.home_pose,point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
-
|
|
|
|
- self.arm.set_path_constraints(path_constraints)#设定约束
|
|
|
|
- self.arm.set_pose_target(point, self.end_effector_link)#设定目标点为传入的点
|
|
|
|
- self.arm.set_start_state(state)#起点位置设置为规划组最后一个点 或者当前状态(第一个点时)
|
|
|
|
|
|
+ # def create_path_constraints(self,start_point,end_point,r):
|
|
|
|
+ # #计算起点指向终点的向量
|
|
|
|
+ # vector = np.array([end_point[0]- start_point[0], end_point[1]- start_point[1], end_point[2]- start_point[2]])
|
|
|
|
+ # height = np.linalg.norm(vector)+0.16
|
|
|
|
+ # radius = r
|
|
|
|
+
|
|
|
|
+ # # 位置约束
|
|
|
|
+ # position_constraint = PositionConstraint()
|
|
|
|
+ # position_constraint.header.frame_id = "base_link"
|
|
|
|
+ # position_constraint.link_name = self.end_effector_link
|
|
|
|
+ # position_constraint.target_point_offset = Vector3(0, 0, 0)
|
|
|
|
+ # position_constraint.weight = 1.0
|
|
|
|
+
|
|
|
|
+ # #构建 shape_msgs/SolidPrimitive 消息
|
|
|
|
+ # bounding_volume = SolidPrimitive()
|
|
|
|
+ # bounding_volume.type = SolidPrimitive.CYLINDER#圆柱
|
|
|
|
+ # # bounding_volume.dimensions = [0.003,1]
|
|
|
|
+ # bounding_volume.dimensions = [height,radius]
|
|
|
|
+ # position_constraint.constraint_region.primitives.append(bounding_volume)
|
|
|
|
+
|
|
|
|
+ # #构建 geometry_msgs/Pose 消息,用于指定圆柱体在空间中的位置和姿态
|
|
|
|
+ # pose = Pose()
|
|
|
|
+ # pose.position.x = start_point[0] + vector[0] / 2#定义位置(找了个几何中心)
|
|
|
|
+ # pose.position.y = start_point[1] + vector[1] / 2
|
|
|
|
+ # pose.position.z = start_point[2] + vector[2] / 2
|
|
|
|
+ # # 计算圆柱体的姿态
|
|
|
|
+ # z_axis = np.array([0, 0, 1])
|
|
|
|
+ # axis = np.cross(z_axis, vector) #计算两个向量(向量数组)的叉乘 叉乘返回的数组既垂直于a,又垂直于b
|
|
|
|
+ # angle = np.arccos(np.dot(z_axis, vector) / np.linalg.norm(vector))#反余弦求角度
|
|
|
|
+ # q = tf.transformations.quaternion_about_axis(angle, axis)#通过旋转轴和旋转角返回四元数
|
|
|
|
+ # pose.orientation.x = q[0]
|
|
|
|
+ # pose.orientation.y = q[1]
|
|
|
|
+ # pose.orientation.z = q[2]
|
|
|
|
+ # pose.orientation.w = q[3]
|
|
|
|
+ # position_constraint.constraint_region.primitive_poses.append(pose)
|
|
|
|
+
|
|
|
|
+ # constraints = Constraints()
|
|
|
|
+ # constraints.position_constraints.append(position_constraint)
|
|
|
|
+
|
|
|
|
+ # return constraints
|
|
|
|
+
|
|
|
|
+
|
|
|
|
+ # def move_p_flexible(self,point,points,trajectory,trajectory_with_type,a=1,v=1):
|
|
|
|
+ # self.arm.set_max_acceleration_scaling_factor(a)
|
|
|
|
+ # self.arm.set_max_velocity_scaling_factor(v)
|
|
|
|
+ # rrr=0.09 #初始允许半径 9cm
|
|
|
|
+ # er=0
|
|
|
|
+ # if trajectory:
|
|
|
|
+ # #起点位置设置为规划组最后一个点
|
|
|
|
+ # state = self.arm.get_current_state()
|
|
|
|
+ # state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
|
|
|
|
+ # path_constraints = self.create_path_constraints(points[-1],point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
+ # else:
|
|
|
|
+ # #刚开始规划 起点位置设定为当前状态 按理来说是home点
|
|
|
|
+ # self.go_home()
|
|
|
|
+ # self.home_pose=self.get_now_pose()
|
|
|
|
+ # state = self.arm.get_current_state()
|
|
|
|
+ # path_constraints = self.create_path_constraints(self.home_pose,point,rrr)#将当前的点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
+
|
|
|
|
+ # self.arm.set_path_constraints(path_constraints)#设定约束
|
|
|
|
+ # self.arm.set_pose_target(point, self.end_effector_link)#设定目标点为传入的点
|
|
|
|
+ # self.arm.set_start_state(state)#起点位置设置为规划组最后一个点 或者当前状态(第一个点时)
|
|
|
|
|
|
- #尝试规划次数
|
|
|
|
- b = 4 #尝试规划5次 无约束5次
|
|
|
|
- for i in range(b):
|
|
|
|
- traj = self.arm.plan()#调用plan进行规划
|
|
|
|
- error=traj[3]
|
|
|
|
- if error.val == moveit_msgs.msg._MoveItErrorCodes.MoveItErrorCodes.SUCCESS:
|
|
|
|
- trajj = traj[1] #取出规划的信息
|
|
|
|
- rospy.loginfo("正在检查移动轨迹有效性...")
|
|
|
|
- error_c, limit_margin=check.check_joint_positions(trajj)
|
|
|
|
- if not error_c:
|
|
|
|
- rospy.loginfo("本次移动OK")
|
|
|
|
- rospy.loginfo("*******************")
|
|
|
|
- trajj_with_type = mark_the_traj(trajj,"during-p",welding_sequence)
|
|
|
|
- trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
|
|
|
|
- trajj_with_type.points[-1].type = "end"
|
|
|
|
- trajectory_with_type.append(trajj_with_type)
|
|
|
|
- points.append(point)
|
|
|
|
- trajectory.append(trajj)
|
|
|
|
- break
|
|
|
|
- else:
|
|
|
|
- rospy.loginfo("check failed! 移动轨迹无效")
|
|
|
|
- rospy.loginfo("移动规划失败-开始第{}次重新规划".format(i+1))
|
|
|
|
- self.arm.clear_path_constraints()
|
|
|
|
- rrr=rrr+0.2#每次增加20厘米半径
|
|
|
|
- rospy.loginfo("R值:{}".format(rrr))
|
|
|
|
- if trajectory:
|
|
|
|
- path_constraints = self.create_path_constraints2(points[-1],point,rrr)#将最后一个点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
- else:
|
|
|
|
- path_constraints = self.create_path_constraints2(self.home_pose,point,rrr)#将最后一个点和起点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
- self.arm.set_path_constraints(path_constraints)#设定约束
|
|
|
|
- if(i>=(b-2)):
|
|
|
|
- rospy.loginfo("所有移动规划尝试失败 取消路径约束")
|
|
|
|
- self.arm.clear_path_constraints()
|
|
|
|
- if(i==(b-1)):
|
|
|
|
- rospy.loginfo("所有移动规划尝试失败 焊缝起点不可达")
|
|
|
|
- er=1
|
|
|
|
- break
|
|
|
|
- #清除约束
|
|
|
|
- self.arm.clear_path_constraints()
|
|
|
|
|
|
+ # #尝试规划次数
|
|
|
|
+ # b = 4 #尝试规划5次 无约束5次
|
|
|
|
+ # for i in range(b):
|
|
|
|
+ # traj = self.arm.plan()#调用plan进行规划
|
|
|
|
+ # error=traj[3]
|
|
|
|
+ # if error.val == moveit_msgs.msg._MoveItErrorCodes.MoveItErrorCodes.SUCCESS:
|
|
|
|
+ # trajj = traj[1] #取出规划的信息
|
|
|
|
+ # rospy.loginfo("正在检查移动轨迹有效性...")
|
|
|
|
+ # error_c, limit_margin=check.check_joint_positions(trajj)
|
|
|
|
+ # if not error_c:
|
|
|
|
+ # rospy.loginfo("本次移动OK")
|
|
|
|
+ # rospy.loginfo("*******************")
|
|
|
|
+ # trajj_with_type = mark_the_traj(trajj,"during-p",welding_sequence)
|
|
|
|
+ # trajj_with_type.points[-len(trajj.joint_trajectory.points)].type = "start"
|
|
|
|
+ # trajj_with_type.points[-1].type = "end"
|
|
|
|
+ # trajectory_with_type.append(trajj_with_type)
|
|
|
|
+ # points.append(point)
|
|
|
|
+ # trajectory.append(trajj)
|
|
|
|
+ # break
|
|
|
|
+ # else:
|
|
|
|
+ # rospy.loginfo("check failed! 移动轨迹无效")
|
|
|
|
+ # rospy.loginfo("移动规划失败-开始第{}次重新规划".format(i+1))
|
|
|
|
+ # self.arm.clear_path_constraints()
|
|
|
|
+ # rrr=rrr+0.2#每次增加20厘米半径
|
|
|
|
+ # rospy.loginfo("R值:{}".format(rrr))
|
|
|
|
+ # if trajectory:
|
|
|
|
+ # path_constraints = self.create_path_constraints(points[-1],point,rrr)#将最后一个点和输入的点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
+ # else:
|
|
|
|
+ # path_constraints = self.create_path_constraints(self.home_pose,point,rrr)#将最后一个点和起点(焊缝的起始点)做圆柱轨迹约束
|
|
|
|
+ # self.arm.set_path_constraints(path_constraints)#设定约束
|
|
|
|
+ # if(i>=(b-2)):
|
|
|
|
+ # rospy.loginfo("所有移动规划尝试失败 取消路径约束")
|
|
|
|
+ # self.arm.clear_path_constraints()
|
|
|
|
+ # if(i==(b-1)):
|
|
|
|
+ # rospy.loginfo("所有移动规划尝试失败 焊缝起点不可达")
|
|
|
|
+ # er=1
|
|
|
|
+ # break
|
|
|
|
+ # #清除约束
|
|
|
|
+ # self.arm.clear_path_constraints()
|
|
|
|
|
|
- return points,trajectory,trajectory_with_type,er
|
|
|
|
|
|
+ # return points,trajectory,trajectory_with_type,er
|
|
|
|
|
|
|
|
+ pass
|
|
|
|
+
|
|
|
|
|
|
- #TODO go_home
|
|
|
|
- @decorator_time
|
|
|
|
def go_home(self,a=1,v=1):
|
|
def go_home(self,a=1,v=1):
|
|
rospy.loginfo("go_home start")
|
|
rospy.loginfo("go_home start")
|
|
self.arm.set_max_acceleration_scaling_factor(a)
|
|
self.arm.set_max_acceleration_scaling_factor(a)
|
|
@@ -289,23 +288,15 @@ class MoveIt_Control:
|
|
rospy.loginfo("go_home end")
|
|
rospy.loginfo("go_home end")
|
|
# rospy.sleep(1)
|
|
# rospy.sleep(1)
|
|
|
|
|
|
- def go_ready(self,a=1,v=1):
|
|
|
|
- rospy.loginfo("go_ready start")
|
|
|
|
- self.arm.set_max_acceleration_scaling_factor(a)
|
|
|
|
- self.arm.set_max_velocity_scaling_factor(v)
|
|
|
|
- self.arm.set_named_target('ready')
|
|
|
|
- rospy.loginfo("get_ready end")
|
|
|
|
- self.arm.go()
|
|
|
|
- rospy.loginfo("go_ready end")
|
|
|
|
|
|
|
|
- #TODO go_home_justplan
|
|
|
|
- @decorator_time
|
|
|
|
|
|
+
|
|
def go_home_justplan(self,trajectory,trajectory_with_type,a=1,v=1):
|
|
def go_home_justplan(self,trajectory,trajectory_with_type,a=1,v=1):
|
|
rospy.loginfo("go_home start")
|
|
rospy.loginfo("go_home start")
|
|
self.arm.set_max_acceleration_scaling_factor(a)
|
|
self.arm.set_max_acceleration_scaling_factor(a)
|
|
self.arm.set_max_velocity_scaling_factor(v)
|
|
self.arm.set_max_velocity_scaling_factor(v)
|
|
state = self.arm.get_current_state()
|
|
state = self.arm.get_current_state()
|
|
- state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
|
|
|
|
|
|
+ if trajectory:
|
|
|
|
+ state.joint_state.position = trajectory[-1].joint_trajectory.points[-1].positions
|
|
self.arm.set_start_state(state)
|
|
self.arm.set_start_state(state)
|
|
self.arm.set_named_target('home')
|
|
self.arm.set_named_target('home')
|
|
traj = self.arm.plan()
|
|
traj = self.arm.plan()
|
|
@@ -318,7 +309,7 @@ class MoveIt_Control:
|
|
return trajectory,trajectory_with_type
|
|
return trajectory,trajectory_with_type
|
|
|
|
|
|
#TODO path_planning
|
|
#TODO path_planning
|
|
- @decorator_time
|
|
|
|
|
|
+
|
|
def path_planning(self,folder_path,gohome=True):
|
|
def path_planning(self,folder_path,gohome=True):
|
|
file_path_result = os.path.join(folder_path, 'result.txt')
|
|
file_path_result = os.path.join(folder_path, 'result.txt')
|
|
all_data = process_welding_data(file_path_result)
|
|
all_data = process_welding_data(file_path_result)
|
|
@@ -334,9 +325,18 @@ class MoveIt_Control:
|
|
point11 = [start_point[0]/1000, start_point[1]/1000, start_point[2]/1000, q1[0],q1[1],q1[2],q1[3]]
|
|
point11 = [start_point[0]/1000, start_point[1]/1000, start_point[2]/1000, q1[0],q1[1],q1[2],q1[3]]
|
|
point22 = [end_point[0]/1000, end_point[1]/1000, end_point[2]/1000, q2[0],q2[1],q2[2],q2[3]]
|
|
point22 = [end_point[0]/1000, end_point[1]/1000, end_point[2]/1000, q2[0],q2[1],q2[2],q2[3]]
|
|
way_points,trajectory,trajectory_with_type = self.plan_cartesian_path_LLL(point11,point22,way_points,trajectory,trajectory_with_type,v=speed_v)
|
|
way_points,trajectory,trajectory_with_type = self.plan_cartesian_path_LLL(point11,point22,way_points,trajectory,trajectory_with_type,v=speed_v)
|
|
-
|
|
|
|
|
|
+
|
|
rospy.loginfo("第%d条焊缝规划完毕",i+1)
|
|
rospy.loginfo("第%d条焊缝规划完毕",i+1)
|
|
rospy.loginfo("*******************")
|
|
rospy.loginfo("*******************")
|
|
|
|
+
|
|
|
|
+ #向上移动末端执行器
|
|
|
|
+ if i<len(all_data):
|
|
|
|
+ up_value=0.1
|
|
|
|
+ point_up=[point22[0], point22[1], point22[2]-up_value, point22[3], point22[4],point22[5],point22[6]]
|
|
|
|
+ way_points, trajectory, trajectory_with_type = self.plan_cartesian_path_LLL(point22,point_up,way_points,trajectory,trajectory_with_type,v=speed_v)
|
|
|
|
+ rospy.loginfo("末端执行器上移完毕")
|
|
|
|
+ rospy.loginfo("*******************")
|
|
|
|
+
|
|
rospy.loginfo("All of The trajectory Plan successfully")
|
|
rospy.loginfo("All of The trajectory Plan successfully")
|
|
rospy.loginfo("*******************")
|
|
rospy.loginfo("*******************")
|
|
if gohome:
|
|
if gohome:
|
|
@@ -454,6 +454,7 @@ def ROS2PY_msgs(msgs, m_sr):
|
|
py_msgs.fail = m_sr.hf_fail.copy()
|
|
py_msgs.fail = m_sr.hf_fail.copy()
|
|
py_msgs.shun_xv = msgs.points[0].sequence.copy()
|
|
py_msgs.shun_xv = msgs.points[0].sequence.copy()
|
|
|
|
|
|
|
|
+ # 打印规划信息
|
|
# for i in range(len(py_msgs.point.type)):
|
|
# for i in range(len(py_msgs.point.type)):
|
|
# print(py_msgs.point.xyz_list[i])
|
|
# print(py_msgs.point.xyz_list[i])
|
|
# print(py_msgs.point.type[i])
|
|
# print(py_msgs.point.type[i])
|
|
@@ -469,40 +470,49 @@ def ROS2PY_msgs(msgs, m_sr):
|
|
# moveit_server.move_j(py_msgs.point.xyz_list[i])
|
|
# moveit_server.move_j(py_msgs.point.xyz_list[i])
|
|
# #input("任意键继续")
|
|
# #input("任意键继续")
|
|
|
|
|
|
-def get_valid_input(factor, default):
|
|
|
|
- while True:
|
|
|
|
- user_input=input(factor)
|
|
|
|
- if user_input=="":
|
|
|
|
- return default
|
|
|
|
- try:
|
|
|
|
- value=float(user_input)
|
|
|
|
- if 0<value<=1:
|
|
|
|
- return value
|
|
|
|
- else:
|
|
|
|
- rospy.logerr("缩放因子必须在(0, 1]范围内,请重新输入!")
|
|
|
|
- except ValueError:
|
|
|
|
- rospy.logerr("输入值无效,请根据提示重新输入!")
|
|
|
|
-
|
|
|
|
-def get_user_input():
|
|
|
|
- """获取用户输入的速度和加速度缩放因子,并在控制台中打印信息和错误提示"""
|
|
|
|
- DEFUALT_V = 1.0
|
|
|
|
- DEFUALT_A = 1.0
|
|
|
|
|
|
+# def get_valid_input(factor, default):
|
|
|
|
+# while True:
|
|
|
|
+# user_input=input(factor)
|
|
|
|
+# if user_input=="":
|
|
|
|
+# return default
|
|
|
|
+# try:
|
|
|
|
+# value=float(user_input)
|
|
|
|
+# if 0<value<=1:
|
|
|
|
+# return value
|
|
|
|
+# else:
|
|
|
|
+# rospy.logerr("缩放因子必须在(0, 1]范围内,请重新输入!")
|
|
|
|
+# except ValueError:
|
|
|
|
+# rospy.logerr("输入值无效,请根据提示重新输入!")
|
|
|
|
+
|
|
|
|
+# def get_user_input():
|
|
|
|
+# """获取用户输入的速度和加速度缩放因子,并在控制台中打印信息和错误提示"""
|
|
|
|
+# DEFUALT_V = 1.0
|
|
|
|
+# DEFUALT_A = 1.0
|
|
|
|
|
|
- try:
|
|
|
|
- termios.tcflush(sys.stdin, termios.TCIFLUSH) #清空输入缓存
|
|
|
|
- rospy.loginfo("输入缓存区已清空!")
|
|
|
|
|
|
+# try:
|
|
|
|
+# termios.tcflush(sys.stdin, termios.TCIFLUSH) #清空输入缓存
|
|
|
|
+# rospy.loginfo("输入缓存区已清空!")
|
|
|
|
|
|
- vv=get_valid_input("请输入速度缩放因子(0-1, 默认为1): ", DEFUALT_V)
|
|
|
|
- #a=get_valid_input("请输入加速度缩放因子(0-1, 默认为1): ", DEFUALT_A)
|
|
|
|
|
|
+# vv=get_valid_input("请输入速度缩放因子(0-1, 默认为1): ", DEFUALT_V)
|
|
|
|
+# #a=get_valid_input("请输入加速度缩放因子(0-1, 默认为1): ", DEFUALT_A)
|
|
|
|
|
|
- #rospy.loginfo(f"用户输入的速度缩放因子为{vv}")
|
|
|
|
- return vv
|
|
|
|
- except Exception as e:
|
|
|
|
- rospy.logerr(f"发生错误:{e}")
|
|
|
|
|
|
+# #rospy.loginfo(f"用户输入的速度缩放因子为{vv}")
|
|
|
|
+# return vv
|
|
|
|
+# except Exception as e:
|
|
|
|
+# rospy.logerr(f"发生错误:{e}")
|
|
|
|
+
|
|
|
|
+# def ROS2_msgs_write(msgs, m_sr):
|
|
|
|
+# for i in range(len(msgs.points)):
|
|
|
|
+# py_msgs.point.xyz_list.append(msgs.points[i].positions)
|
|
|
|
+
|
|
|
|
+# f_p = os.path.join(folder_path, 'outtt.txt')
|
|
|
|
+# with open(f_p,'w') as file:
|
|
|
|
+# for point in py_msgs.point.xyz_list:
|
|
|
|
+# file.write(' '.join(str(value) for value in point)+ "\n")
|
|
|
|
|
|
|
|
|
|
if __name__ =="__main__":
|
|
if __name__ =="__main__":
|
|
- # from redis_publisher import Publisher
|
|
|
|
|
|
+ # from redis_publisher import Publisher #注意 可能是史前redis
|
|
# publisher = Publisher()
|
|
# publisher = Publisher()
|
|
|
|
|
|
folder_path = rospy.get_param("folder_path")
|
|
folder_path = rospy.get_param("folder_path")
|
|
@@ -510,15 +520,16 @@ if __name__ =="__main__":
|
|
moveit_server = MoveIt_Control(is_use_gripper=False)
|
|
moveit_server = MoveIt_Control(is_use_gripper=False)
|
|
welding_sequence = rospy.get_param('welding_sequence')
|
|
welding_sequence = rospy.get_param('welding_sequence')
|
|
|
|
|
|
- speed_v=1
|
|
|
|
|
|
+ speed_v=0.001
|
|
# speed_v=get_user_input()
|
|
# speed_v=get_user_input()
|
|
# rospy.loginfo(f"用户输入的速度缩放因子为{speed_v}")
|
|
# rospy.loginfo(f"用户输入的速度缩放因子为{speed_v}")
|
|
|
|
|
|
trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning(folder_path)
|
|
trajectory,trajectory_merge,trajectory_with_type_merge = moveit_server.path_planning(folder_path)
|
|
|
|
|
|
- #moveit_server.go_ready()
|
|
|
|
|
|
+ #moveit_server.go_ready() #合并后的轨迹也需要从ready点开始执行
|
|
rospy.loginfo("开始执行合并后轨迹")
|
|
rospy.loginfo("开始执行合并后轨迹")
|
|
moveit_server.arm.execute(trajectory_merge)
|
|
moveit_server.arm.execute(trajectory_merge)
|
|
|
|
+ #ROS2_msgs_write(trajectory_with_type_merge,moveit_server)
|
|
rospy.loginfo("合并后轨迹执行完毕")
|
|
rospy.loginfo("合并后轨迹执行完毕")
|
|
|
|
|
|
rospy.set_param("sign_control",0)
|
|
rospy.set_param("sign_control",0)
|