def linear_movement(self,position, linear_speed = 0.2, linear_accel = 0.2, rotational_speed = 0.1, rotational_accel = 0.1): try: traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options = traj_options, limb = self._limb) wpt_opts = MotionWaypointOptions(max_linear_speed=linear_speed, max_linear_accel=linear_accel, max_rotational_speed=rotational_speed, max_rotational_accel=rotational_accel, max_joint_speed_ratio=0.2) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = self._limb) poseStamped = PoseStamped() poseStamped.pose = position waypoint.set_cartesian_pose(poseStamped, self._tip_name) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=5.0) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. Exiting before trajectory completion.')
def goToPose(self): limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions(max_linear_speed=0.1, max_linear_accel=0.1, max_rotational_speed=0.1, max_rotational_accel=0.1, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() waypoint.set_joint_angles(self.ikResults.values(), "left_hand", joint_names) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=30.0) if result is None: rospy.logerr('Trajectory Failed') return if result.result: rospy.loginfo('Trajectory Success') else: rospy.logerr('Trajectory failed with error %s', result.errorId)
def get_in_contact_opts(self): interaction_options = self.set_interaction_params() if interaction_options: trajectory_options = TrajectoryOptions() trajectory_options.interaction_control = True trajectory_options.interpolation_type = self._trajType trajectory_options.interaction_params = interaction_options.to_msg() return trajectory_options else: return None
def move(self, point_list, wait = True, MAX_LIN_SPD=7.0, MAX_LIN_ACCL=1.5): # one point = [x_coord, y_coord, z_coord, x_deg, y_deg, z_deg] try: limb = Limb() # point_list = [pointA, pointB, pointC, ...] traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) except: print("There may have been an error while exiting") if self.STOP: traj.stop_trajectory() return True wpt_opts = MotionWaypointOptions(max_linear_speed=MAX_LIN_SPD, max_linear_accel=MAX_LIN_ACCL, corner_distance=0.002) for point in point_list: q_base = quaternion_from_euler(0, 0, math.pi/2) #q_rot = quaternion_from_euler(math.radians(point[3]), math.radians(point[4]), math.radians(point[5])) q_rot = quaternion_from_euler(point[3], point[4], point[5]) q = quaternion_multiply(q_rot, q_base) newPose = PoseStamped() newPose.header = Header(stamp=rospy.Time.now(), frame_id='base') newPose.pose.position.x = point[0] + 0.65 newPose.pose.position.y = point[1] + 0.0 newPose.pose.position.z = point[2] + 0.4 newPose.pose.orientation.x = q[0] newPose.pose.orientation.y = q[1] newPose.pose.orientation.z = q[2] newPose.pose.orientation.w = q[3] waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) waypoint.set_cartesian_pose(newPose, "right_hand", limb.joint_ordered_angles()) traj.append_waypoint(waypoint.to_msg()) if(wait): print(" \n --- Sending trajectory and waiting for finish --- \n") result = traj.send_trajectory(wait_for_result=wait) if result is None: rospy.logerr('Trajectory FAILED to send') success = False elif result.result: rospy.loginfo('Motion controller successfully finished the trajcetory') success = True else: rospy.logerr('Motion controller failed to complete the trajectory. Error: %s', result.errorId) success = False else: print("\n --- Sending trajector w/out waiting --- \n") traj.send_trajectory(wait_for_result=wait) success = True return success
def set_trajectory_options(self, trajectory_options=None): """ @param trajectory_options: options for the trajectory if trajectory_options is None: use default options """ # TODO: Better support for interaction control options. if trajectory_options is None: trajectory_options = TrajectoryOptions() trajectory_options.interpolation_type = TrajectoryOptions.JOINT if not isinstance(trajectory_options, TrajectoryOptions): rospy.logerr('Cannot append options: invalid instance type!') else: self._traj.trajectory_options = deepcopy(trajectory_options)
def go_to_pose(self, position, orientation): try: traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=self._right_arm) wpt_opts = MotionWaypointOptions(max_linear_speed=0.6, max_linear_accel=0.6, max_rotational_speed=1.57, max_rotational_accel=1.57, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=self._right_arm) pose = Pose() pose.position.x = position[0] pose.position.y = position[1] pose.position.z = position[2] pose.orientation.x = orientation[0] pose.orientation.y = orientation[1] pose.orientation.z = orientation[2] pose.orientation.w = orientation[0] poseStamped = PoseStamped() poseStamped.pose = pose joint_angles = self._right_arm.joint_ordered_angles() waypoint.set_cartesian_pose(poseStamped, "right_hand", joint_angles) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=10) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!') else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr( 'Keyboard interrupt detected from the user. Exiting before trajectory completion.' )
def moveRoboticArm(position, orientation, linear_speed, linear_accel): """ Move the robot arm to the specified configuration given a positionX, positionY, positionZ, quaternion array and max linear speed. """ try: limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions(max_linear_speed=linear_speed, max_linear_accel=linear_accel) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() endpoint_state = limb.tip_state('right_hand') pose = endpoint_state.pose if position is not None and len(position) == 3: pose.position.x = position[0] pose.position.y = position[1] pose.position.z = position[2] if orientation is not None and len(orientation) == 4: pose.orientation.x = orientation[0] pose.orientation.y = orientation[1] pose.orientation.z = orientation[2] pose.orientation.w = orientation[3] poseStamped = PoseStamped() poseStamped.pose = pose joint_angles = limb.joint_ordered_angles() waypoint.set_cartesian_pose(poseStamped, 'right_hand', joint_angles) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory() if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!') else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: print("Something went wrong") rospy.logerr( 'Keyboard interrupt detected from the user. Exiting before trajectory completion.' )
def goto_cartesian(self, x, y, z): print("goto_cartesian called with x={}, y={}, z={}".format(x, y, z)) limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions() waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() endpoint_state = limb.tip_state('right_hand') if endpoint_state is None: print('Endpoint state not found') return self.MOVE_ERROR pose = endpoint_state.pose pose.position.x = x pose.position.y = y pose.position.z = z pose.orientation.x = self.orientation_x pose.orientation.y = self.orientation_y pose.orientation.z = self.orientation_z pose.orientation.w = self.orientation_w poseStamped = PoseStamped() poseStamped.pose = pose waypoint.set_cartesian_pose(poseStamped, 'right_hand', []) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory() if result is None: print("Trajectory FAILED to send") return self.MOVE_ERROR if result.result: print('Motion controller successfully finished the trajectory!') self.cur_x = x self.cur_y = y self.cur_z = z return self.MOVE_SUCCESS else: print('Motion controller failed to complete the trajectory %s', result.errorId) return self.MOVE_ERROR
def __init__(self): self.robot_state = 0 # normal self.breath_state =0 # false rospy.Subscriber("cs_sawyer/head_light", UInt8, self.callback_update_breath1) rospy.Subscriber("cs_sawyer/breath", Bool, self.callback_update_breath2) self.rospack = rospkg.RosPack() # Set the trajectory options self.limb = Limb() traj_opts = TrajectoryOptions() traj_opts.interpolation_type = 'JOINT' self.traj = MotionTrajectory(trajectory_options = traj_opts, limb = self.limb) # Set the waypoint options wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=0.05, joint_tolerances=0.7) #max_joint_accel=0.1) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = self.limb) # Append a waypoint at the current pose waypoint.set_joint_angles(self.limb.joint_ordered_angles()) #self.traj.append_waypoint(waypoint.to_msg()) #self.limb.set_joint_position_speed(0.3) with open(join(self.rospack.get_path("cs_sawyer"), "config/poses.json")) as f: self.poses = json.load(f) joint_angles= [self.poses["pause"][j] for j in [ 'right_j0', 'right_j1', 'right_j2', 'right_j3', 'right_j4', 'right_j5', 'right_j6']] j1= joint_angles[1] j2= joint_angles[2] x=0 while x < 16*pi: new_j1 = 0.07*sin(x)+j1 new_j2=0.09*sin(0.5*x)+j2 joint_angles[1]=new_j1 joint_angles[2]=new_j2 x=x+pi/40 waypoint.set_joint_angles(joint_angles = joint_angles) self.traj.append_waypoint(waypoint.to_msg())
def gripper_pose(x, y, z): limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions() waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() endpoint_state = limb.tip_state('right_hand') if endpoint_state is None: print('Endpoint state not found') return False pose = endpoint_state.pose pose.position.x = x pose.position.y = y pose.position.z = z pose.orientation.x = 0 pose.orientation.y = 0 pose.orientation.z = 0 pose.orientation.w = 1 poseStamped = PoseStamped() poseStamped.pose = pose waypoint.set_cartesian_pose(poseStamped, 'right_hand', []) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory() if result is None: print("Trajectory FAILED to send") return False if result.result: return True else: print('Motion controller failed to complete the trajectory %s', result.errorId) return False
def execute_trajectory(self, trajectory, joint_names, speed=None, acceleration=None): """ trajectory is a list of points: approach (joint), init (cart), drawing (cart), retreat (cart) """ speed = speed if speed is not None else self.speed acceleration = acceleration if acceleration is not None else self.acceleration if isinstance(trajectory, dict) and "approach" in trajectory: for mtype in ["approach", "init", "drawing", "retreat"]: points = trajectory[mtype] if points["type"] == "joint": self._seed = points["joints"] self.move_to_joint_positions( dict(zip(joint_names, points["joints"]))) elif points["type"] == "cart": wpt_opts = MotionWaypointOptions( max_joint_speed_ratio=speed, max_joint_accel=acceleration) traj = MotionTrajectory(limb=self.limb) waypoint = MotionWaypoint(options=wpt_opts, limb=self.limb) t_opt = TrajectoryOptions( interpolation_type=TrajectoryOptions.CARTESIAN) jv = deepcopy(points["joints"]) jv.reverse() waypoint.set_joint_angles(jv) waypoint.set_cartesian_pose( list_to_pose_stamped(points["pose"], frame_id="base")) traj.append_waypoint(waypoint) jn = [str(j) for j in joint_names] jn.reverse() traj.set_joint_names(jn) traj.set_trajectory_options(t_opt) result = traj.send_trajectory(timeout=10) self.last_activity = rospy.Time.now() if result is None: rospy.logerr("Trajectory failed to send") elif not result.result: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) else: rospy.logwarn("Unknown type %", mtype) else: rospy.logerr("Incorrect inputs to execute_trajectory") return
def __init__(self): self.mover = move_to_point.MoveToPoint() self.retrieve_height = -0.015 self._limb = Limb() self.traj_options = TrajectoryOptions() self.traj_options.interpolation_type = TrajectoryOptions.CARTESIAN self.traj = MotionTrajectory(trajectory_options=self.traj_options, limb=self._limb) self.wpt_options = MotionWaypointOptions(max_linear_speed=0.4, max_linear_accel=0.4, max_rotational_speed=1.57, max_rotational_accel=1.57, max_joint_speed_ratio=1.0) self.waypoint = MotionWaypoint(options=self.wpt_options.to_msg(), limb=self._limb) self.joint_names = self._limb.joint_names() endpoint_state = self._limb.tip_state('right_hand') self.pose = endpoint_state.pose
def main(): """ Move the robot arm to the specified configuration. Call using: $ rosrun intera_examples go_to_cartesian_pose.py [arguments: see below] -p 0.4 -0.3 0.18 -o 0.0 1.0 0.0 0.0 -t right_hand --> Go to position: x=0.4, y=-0.3, z=0.18 meters --> with quaternion orientation (0, 1, 0, 0) and tip name right_hand --> The current position or orientation will be used if only one is provided. -q 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 --> Go to joint angles: 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 using default settings --> If a Cartesian pose is not provided, Forward kinematics will be used --> If a Cartesian pose is provided, the joint angles will be used to bias the nullspace -R 0.01 0.02 0.03 0.1 0.2 0.3 -T -> Jog arm with Relative Pose (in tip frame) -> x=0.01, y=0.02, z=0.03 meters, roll=0.1, pitch=0.2, yaw=0.3 radians -> The fixed position and orientation paramters will be ignored if provided """ epilog = """ See help inside the example with the '?' key for key bindings. """ rp = intera_interface.RobotParams() valid_limbs = rp.get_limb_names() if not valid_limbs: rp.log_message(("Cannot detect any limb parameters on this robot. " "Exiting."), "ERROR") return arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__doc__, epilog=epilog) parser.add_argument("-r", "--record_point_pose", type=bool, default=0, nargs='+', help="record pose or not") parser.add_argument("-p", "--position", type=float, nargs='+', help="Desired end position: X, Y, Z") parser.add_argument("-o", "--orientation", type=float, nargs='+', help="Orientation as a quaternion (x, y, z, w)") parser.add_argument( "-R", "--relative_pose", type=float, nargs='+', help= "Jog pose by a relative amount in the base frame: X, Y, Z, roll, pitch, yaw" ) parser.add_argument( "-T", "--in_tip_frame", action='store_true', help="For relative jogs, job in tip frame (default is base frame)") parser.add_argument( "-q", "--joint_angles", type=float, nargs='+', default=[], help="A list of joint angles, one for each of the 7 joints, J0...J6") parser.add_argument("-t", "--tip_name", default='right_hand', help="The tip name used by the Cartesian pose") parser.add_argument("--linear_speed", type=float, default=0.6, help="The max linear speed of the endpoint (m/s)") parser.add_argument( "--linear_accel", type=float, default=0.6, help="The max linear acceleration of the endpoint (m/s/s)") parser.add_argument( "--rotational_speed", type=float, default=1.57, help="The max rotational speed of the endpoint (rad/s)") parser.add_argument( "--rotational_accel", type=float, default=1.57, help="The max rotational acceleration of the endpoint (rad/s/s)") parser.add_argument( "--timeout", type=float, default=None, help= "Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout." ) parser.add_argument( "-l", "--limb", dest="limb", default=valid_limbs[0], choices=valid_limbs, help="Limb on which to run the gripper keyboard example") args = parser.parse_args(rospy.myargv()[1:]) try: rospy.init_node('go_to_cartesian_pose_py') limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions( max_linear_speed=args.linear_speed, max_linear_accel=args.linear_accel, max_rotational_speed=args.rotational_speed, max_rotational_accel=args.rotational_accel, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() rate = rospy.Rate(10) # 10hz if args.record_point_pose: origin_trans = get_position_now(limb) return None base_quaternions = np.array([0.0, 0.0, 1.0, 0.0]) bin_point = np.array([0.35216134766, 0.621893054464, 0.371810527511]) base_angle = 0.0 while not rospy.is_shutdown(): ch = raw_input("waiting for next step:") if ch == 'r': origin_trans = get_position_now(limb) if ch == 'g': map_keyboard(args.limb) if ch == 'p': coordinates_text = raw_input("type in coordinates:") base_angle = float(coordinates_text) # if float(coordinates_text)>np.pi: # base_rotated_angle=2*np.pi-float(coordinates_text) # else: # base_rotated_angle=np.pi-float(coordinates_text) # base_firest=np.array([0.0,0.0,1.0,0.0]) # base_quaternions=quaternions_after_rotation(base_firest,base_rotated_angle) # print("After reset the rotated, base quaternions are:") # print(base_quaternions) if ch == 'drop': coordinates_text = raw_input("type in coordinates:") bin_point = np.array([ float(coordinates_text.split()[0]), float(coordinates_text.split()[1]), float(coordinates_text.split()[2]) ]) if ch == 'q': return None if ch == 'd': only_grip(args.limb, 'q') coordinates_text = raw_input("type in coordinates:") target_point = np.array([ float(coordinates_text.split()[0]), float(coordinates_text.split()[1]), float(coordinates_text.split()[2]) ]) pick_angle = float(coordinates_text.split()[3]) pick_angle = float(coordinates_text.split()[3]) - base_angle pick_angle = -pick_angle temp = base_quaternions target_after = quaternions_after_rotation(temp, pick_angle) grip_rotated_this_time = target_after pick_quaternions = [ float(grip_rotated_this_time[1]), float(grip_rotated_this_time[2]), float(grip_rotated_this_time[3]), float(grip_rotated_this_time[0]) ] traj_1 = MotionTrajectory(trajectory_options=traj_options, limb=limb) waypoint_1 = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) result_up = go_to_the_point( target_point, args=args, limb=limb, waypoint=waypoint_1, traj=traj_1, target_quaterniond=pick_quaternions) only_grip(args.limb, 'o') matrix = quaternions.quat2mat([ pick_quaternions[3], pick_quaternions[0], pick_quaternions[1], pick_quaternions[2] ]) down_point = target_point + np.dot(matrix, down_distance) traj_2 = MotionTrajectory(trajectory_options=traj_options, limb=limb) waypoint_2 = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) result_down = go_to_the_point( down_point, args=args, limb=limb, waypoint=waypoint_2, traj=traj_2, target_quaterniond=pick_quaternions) only_grip(args.limb, 'q') traj_3 = MotionTrajectory(trajectory_options=traj_options, limb=limb) waypoint_3 = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) result_up = go_to_the_point( target_point, args=args, limb=limb, waypoint=waypoint_3, traj=traj_3, target_quaterniond=pick_quaternions) traj_4 = MotionTrajectory(trajectory_options=traj_options, limb=limb) waypoint_4 = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) result_up = go_to_the_point( bin_point, args, limb, waypoint_4, traj_4, target_quaterniond=pick_quaternions) only_grip(args.limb, 'o') if ch == 's': coordinates_text = raw_input( "type in coordinates and rotation angle:") target_point = [ float(coordinates_text.split()[0]), float(coordinates_text.split()[1]), float(coordinates_text.split()[2]) ] rotatain_angle_from_base = float( coordinates_text.split()[3]) - base_angle rotatain_angle_from_base = -rotatain_angle_from_base temp = base_quaternions target_after = quaternions_after_rotation( temp, rotatain_angle_from_base) grip_rotated_this_time = target_after target_quaterniond = [ float(grip_rotated_this_time[1]), float(grip_rotated_this_time[2]), float(grip_rotated_this_time[3]), float(grip_rotated_this_time[0]) ] traj_new = MotionTrajectory(trajectory_options=traj_options, limb=limb) waypoint_new = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) result = go_to_the_point(target_point, args=args, limb=limb, waypoint=waypoint_new, traj=traj_new, target_quaterniond=target_quaterniond) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!' ) else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr( 'Keyboard interrupt detected from the user. Exiting before trajectory completion.' )
def __init__(self): wx.Frame.__init__(self, None, -1, WINDOWS_TITLE, style=wx.DEFAULT_FRAME_STYLE ^ wx.RESIZE_BORDER) # 默认style是下列项的组合:wx.MINIMIZE_BOX | wx.MAXIMIZE_BOX | wx.RESIZE_BORDER | wx.SYSTEM_MENU | wx.CAPTION | wx.CLOSE_BOX | wx.CLIP_CHILDREN # 创建面板 panel = wx.Panel(self, -1) # 利用wxpython的GridBagSizer()进行页面布局 sizer = wx.GridBagSizer(1, 2) # 列间隔为1,行间隔为2 # self.SetBackgroundColour(wx.Colour(224, 224, 0)) #更改窗口背景颜色 # self.SetSize((860, 640)) #设置窗口大小 self.Center() # 窗口出现时,使其位于显示器的中央 # 设置背景图片 main_image = wx.Image(APP_backgrand_picture, wx.BITMAP_TYPE_ANY) main_image = main_image.ConvertToBitmap() window_size = main_image.GetWidth(), main_image.GetHeight() self.background_image = wx.StaticBitmap(parent=panel, bitmap=main_image) self.SetSize(window_size) #设置窗口大小 # 以下代码处理图标 icon = wx.EmptyIcon() # # 使用其他图像文件作为图标 icon.CopyFromBitmap( wx.BitmapFromImage( wx.Image(APP_picture3, wx.BITMAP_TYPE_JPEG).Rescale(60, 60))) # icon = wx.Icon(APP_icon1, wx.BITMAP_TYPE_ICO) # 读取图标文件 self.SetIcon(icon) """ 以上文件是设置窗口大小和图标,背景图片或者背景颜色。 下面三行设置按钮的方法是一样的,形式却不一样。 wx.Button(panel, 7, "X +") wx.Button(parent=panel, id=7, label="X +") wx.Button(parent=panel, id=7, label="X +", pos=(100,24)) """ self.distance = 0.01 self.delta = 0.1 self.tip_name = 'right_hand' # 调用saywer机器人的机械臂类,获取机械的消息 self.limb = intera_interface.Limb("right") # 确认夹爪是否安装 try: self.gripper = intera_interface.Gripper( 'right_gripper') #夹爪类,控制夹爪开合 except: self.has_gripper = False rospy.loginfo("The electric gripper is not detected on the robot.") else: self.has_gripper = True self.joints = self.limb.joint_names() #关节名字,以列表输出。 # 设置轨迹运动的选项 self.traj_options = TrajectoryOptions() self.traj_options.interpolation_type = 'JOINT' self.traj = MotionTrajectory(trajectory_options=self.traj_options, limb=self.limb) # 设置默认机器人移动速比和移动精度 self._max_joint_speed_ratio = 0.2 self._max_joint_accel = 0.1 self.wpt_opts = MotionWaypointOptions( max_joint_speed_ratio=self._max_joint_speed_ratio, max_joint_accel=self._max_joint_accel) self.waypoint = MotionWaypoint(options=self.wpt_opts.to_msg(), limb=self.limb) """ 设置窗体布局,添加按钮和文本框。 使用静态文本框显示位姿和关节角度; 使用按键设置实现机器人运动 使用滑动条调节运动速比和运动精度以及每次运动距离 """ #***************文本框设置********************** #显示位姿 直角坐标和四元数 result_pose = self.limb.tip_state(self.tip_name).pose display_pose = u'位置:\n' display_pose += '\t' + 'X: ' + str( "%.4f" % result_pose.position.x) + '\n' display_pose += '\t' + 'y: ' + str( "%.4f" % result_pose.position.y) + '\n' display_pose += '\t' + 'Z: ' + str( "%.4f" % result_pose.position.z) + '\n' display_pose += u'姿态:\n' display_pose += '\t' + 'X: ' + str( "%.4f" % result_pose.orientation.x) + '\n' display_pose += '\t' + 'Y: ' + str( "%.4f" % result_pose.orientation.y) + '\n' display_pose += '\t' + 'Z: ' + str( "%.4f" % result_pose.orientation.z) + '\n' display_pose += '\t' + 'W: ' + str( "%.4f" % result_pose.orientation.w) + '\n' self.text_pose = wx.StaticText(panel, style=wx.TE_MULTILINE | wx.HSCROLL) sizer.Add(self.text_pose, pos=(0, 0), flag=wx.ALL, border=5) self.text_pose.SetLabel(display_pose) #显示关节角度 result_joints_angles = self.limb.joint_angles() display_angles = '' for key, value in result_joints_angles.items(): display_angles = key[6:8] + ': ' + str( "%.6f" % value) + '\n' + display_angles display_angles = u'关节角度:\n' + display_angles self.text_joint_angles = wx.StaticText(panel, style=wx.TE_MULTILINE | wx.HSCROLL) sizer.Add(self.text_joint_angles, pos=(0, 1), flag=wx.ALL, border=5) self.text_joint_angles.SetLabel(display_angles) # 显示按键的label self.text1 = wx.StaticText(panel, label="按键label") sizer.Add(self.text1, pos=(2, 0), flag=wx.ALL, border=5) #****************按钮设置********************** # 直角坐标运动 btn_X_up = wx.Button(panel, -1, "X +") #定义按钮 sizer.Add(btn_X_up, pos=(4, 0), flag=wx.ALL, border=5) #布局按钮位置 self.Bind(wx.EVT_BUTTON, self.move_line, btn_X_up) # 触发按钮 btn_X_down = wx.Button(panel, -1, "X -") sizer.Add(btn_X_down, pos=(4, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_line, btn_X_down) btn_Y_up = wx.Button(panel, -1, "Y +") sizer.Add(btn_Y_up, pos=(5, 0), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_line, btn_Y_up) btn_Y_down = wx.Button(panel, -1, "Y -") sizer.Add(btn_Y_down, pos=(5, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_line, btn_Y_down) btn_Z_up = wx.Button(panel, -1, "Z +") sizer.Add(btn_Z_up, pos=(6, 0), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_line, btn_Z_up) btn_Z_down = wx.Button(panel, -1, "Z -") sizer.Add(btn_Z_down, pos=(6, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_line, btn_Z_down) # 夹爪按钮 btn_griper_open = wx.Button(panel, -1, "open") sizer.Add(btn_griper_open, pos=(7, 0), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_griper, btn_griper_open) btn_griper_close = wx.Button(panel, -1, "close") sizer.Add(btn_griper_close, pos=(7, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_griper, btn_griper_close) btn_griper_calibration = wx.Button(panel, -1, "calibrate") sizer.Add(btn_griper_calibration, pos=(7, 3), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_griper, btn_griper_calibration) # 关节运动按钮 btn_j0_up = wx.Button(panel, -1, "J0 +") sizer.Add(btn_j0_up, pos=(1, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j0_up) btn_j0_down = wx.Button(panel, -1, "J0 -") sizer.Add(btn_j0_down, pos=(1, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j0_down) btn_j1_up = wx.Button(panel, -1, "J1 +") sizer.Add(btn_j1_up, pos=(2, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j1_up) btn_j1_down = wx.Button(panel, -1, "J1 -") sizer.Add(btn_j1_down, pos=(2, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j1_down) btn_j2_up = wx.Button(panel, -1, "J2 +") sizer.Add(btn_j2_up, pos=(3, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j2_up) btn_j2_down = wx.Button(panel, -1, "J2 -") sizer.Add(btn_j2_down, pos=(3, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j2_down) btn_j3_up = wx.Button(panel, -1, "J3 +") sizer.Add(btn_j3_up, pos=(4, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j3_up) btn_j3_down = wx.Button(panel, -1, "J3 -") sizer.Add(btn_j3_down, pos=(4, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j3_down) btn_j4_up = wx.Button(panel, -1, "J4 +") sizer.Add(btn_j4_up, pos=(5, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j4_up) btn_j4_down = wx.Button(panel, -1, "J4 -") sizer.Add(btn_j4_down, pos=(5, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j4_down) btn_j5_up = wx.Button(panel, -1, "J5 +") sizer.Add(btn_j5_up, pos=(6, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j5_up) btn_j5_down = wx.Button(panel, -1, "J5 -") sizer.Add(btn_j5_down, pos=(6, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j5_down) btn_j6_up = wx.Button(panel, -1, "J6 +") sizer.Add(btn_j6_up, pos=(7, 4), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j6_up) btn_j6_down = wx.Button(panel, -1, "J6 -") sizer.Add(btn_j6_down, pos=(7, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_BUTTON, self.move_joint, btn_j6_down) #****************滑动条设置*************** # 滑动条文本 text2 = wx.StaticText(panel, label=u"移动速比") sizer.Add(text2, pos=(8, 0), flag=wx.ALL, border=5) slider_bar_speed = wx.Slider(parent=panel, id=-1, value=self._max_joint_speed_ratio * 100, minValue=1, maxValue=100, size=(200, 50), style=wx.SL_AUTOTICKS | wx.SL_LABELS, name=u'移动速比') # slider_bar_speed.SetTick(1) # 滑块刻度间隔 slider_bar_speed.SetPageSize(1) #每次滑块移动距离 sizer.Add(slider_bar_speed, pos=(8, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_SLIDER, self.set_speed, slider_bar_speed) # 滑动条文本 text3 = wx.StaticText(panel, label=u"精确度") sizer.Add(text3, pos=(9, 0), flag=wx.ALL, border=5) slider_bar_sccel = wx.Slider(parent=panel, id=-1, value=1, minValue=self._max_joint_accel * 100, maxValue=100, size=(200, 50), style=wx.SL_AUTOTICKS | wx.SL_LABELS | wx.SL_TOP, name=u'精确度') # slider_bar_sccel.SetTickFreq(1, 1) # 滑块刻度间隔 slider_bar_sccel.SetPageSize(1) #每次滑块移动距离 sizer.Add(slider_bar_sccel, pos=(9, 1), flag=wx.ALL, border=5) self.Bind(wx.EVT_SLIDER, self.set_speed, slider_bar_sccel) text4 = wx.StaticText(panel, label=u"直角坐标系每次移动距离") sizer.Add(text4, pos=(8, 4), flag=wx.ALL, border=5) slider_bar_distance = wx.Slider(parent=panel, id=-1, value=self.distance * 1000, minValue=0, maxValue=60, size=(200, 50), style=wx.SL_AUTOTICKS | wx.SL_LABELS | wx.SL_TOP, name=u'直角距离') # slider_bar_distance.SetTickFreq(1, 1) # 滑块刻度间隔 slider_bar_distance.SetPageSize(1) #每次滑块移动距离 sizer.Add(slider_bar_distance, pos=(8, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_SLIDER, self.set_move_distance, slider_bar_distance) text5 = wx.StaticText(panel, label=u"关节坐标每次移动距离") sizer.Add(text5, pos=(9, 4), flag=wx.ALL, border=5) slider_bar_delta = wx.Slider(parent=panel, id=-1, value=self.delta * 100, minValue=0, maxValue=100, size=(200, 50), style=wx.SL_AUTOTICKS | wx.SL_LABELS | wx.SL_TOP, name=u'关节距离') # slider_bar_delta.SetTickFreq(1, 1) # 滑块刻度间隔 slider_bar_delta.SetPageSize(1) #每次滑块移动距离 sizer.Add(slider_bar_delta, pos=(9, 5), flag=wx.ALL, border=5) self.Bind(wx.EVT_SLIDER, self.set_move_distance, slider_bar_delta) # 将Panmel适应GridBagSizer()放置 panel.SetSizerAndFit(sizer)
def go_to_cartesian_pose(self, position = None, orientation = None, relative_pose = None, in_tip_frame = False, joint_angles = None, tip_name = 'right_hand', linear_speed = 0.6, linear_accel = 0.6, rotational_speed = 1.57, rotational_accel = 1.57, timeout = None, endpoint_pose = None): traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options = traj_options, limb = self) wpt_opts = MotionWaypointOptions(max_linear_speed=linear_speed, max_linear_accel=linear_accel, max_rotational_speed=rotational_speed, max_rotational_accel=rotational_accel, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = self) joint_names = self.joint_names() if joint_angles and len(joint_angles) != len(joint_names): rospy.logerr('len(joint_angles) does not match len(joint_names!)') return None if (position is None and orientation is None and relative_pose is None and endpoint_pose is None): if joint_angles: # does Forward Kinematics waypoint.set_joint_angles(joint_angles, tip_name, joint_names) else: rospy.loginfo("No Cartesian pose or joint angles given. Using default") waypoint.set_joint_angles(joint_angles=None, active_endpoint=args.tip_name) else: endpoint_state = self.tip_state(tip_name) if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', tip_name) return None pose = endpoint_state.pose if relative_pose is not None: if len(relative_pose) != 6: rospy.logerr('Relative pose needs to have 6 elements (x,y,z,roll,pitch,yaw)') return None # create kdl frame from relative pose rot = PyKDL.Rotation.RPY(relative_pose[3], relative_pose[4], relative_pose[5]) trans = PyKDL.Vector(relative_pose[0], relative_pose[1], relative_pose[2]) f2 = PyKDL.Frame(rot, trans) # and convert the result back to a pose message if in_tip_frame: # end effector frame pose = posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base frame pose = posemath.toMsg(f2 * posemath.fromMsg(pose)) else: if endpoint_pose is None: if position is not None and len(position) == 3: pose.position.x = position[0] pose.position.y = position[1] pose.position.z = position[2] if orientation is not None and len(orientation) == 4: pose.orientation.x = orientation[0] pose.orientation.y = orientation[1] pose.orientation.z = orientation[2] pose.orientation.w = orientation[3] else: pose.position.x = endpoint_pose['position'].x pose.position.y = endpoint_pose['position'].y pose.position.z = endpoint_pose['position'].z pose.orientation.x = endpoint_pose['orientation'].x pose.orientation.y = endpoint_pose['orientation'].y pose.orientation.z = endpoint_pose['orientation'].z pose.orientation.w = endpoint_pose['orientation'].w poseStamped = PoseStamped() poseStamped.pose = pose if not joint_angles: # using current joint angles for nullspace bais if not provided joint_angles = self.joint_ordered_angles() print(poseStamped.pose) waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) else: waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) #rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=timeout) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId)
def cart_move_to(self, target_pos, tout=None, relative_mode=False, wait_for_result=True): # # for Motion Controller Interface _trajectory_opts=TrajectoryOptions() _trajectory_opts.interpolation_type=TrajectoryOptions.CARTESIAN # self._motion_trajectory=MotionTrajectory(trajectory_options=_trajectory_opts, limb=self._limb) # # set Waypoint Options _wpt_opts=MotionWaypointOptions(max_linear_speed=self._linear_speed, max_linear_accel=self._linear_accel, max_rotational_speed=self._rotational_speed, max_rotational_accel=self._rotational_accel, max_joint_speed_ratio=1.0) _waypoint=MotionWaypoint(options=_wpt_opts, limb=self._limb) # endpoint_state=self._limb.tip_state(self._tip_name) pose=endpoint_state.pose ######################################## # set target position if relative_mode: # relative position : target_pos -> x, y, z, roll, pitch, yew trans = PyKDL.Vector(target_pos[0],target_pos[1],target_pos[2]) rot = PyKDL.Rotation.RPY(target_pos[3], target_pos[4],target_pos[5]) f2 = PyKDL.Frame(rot, trans) if self._in_tip_frame: # endpoint's cartesian systems pose=posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base's cartesian systems pose=posemath.toMsg(f2 * posemath.fromMsg(pose)) else: # global position : x, y, z, rx, ry, rz, rw pose.position.x=target_pos[0] pose.position.y=target_pos[1] pose.position.z=target_pos[2] pose.orientation.x=target_pos[3] pose.orientation.y=target_pos[4] pose.orientation.z=target_pos[5] pose.orientation.w=target_pos[6] # ########################################### # set target position. poseStamped=PoseStamped() poseStamped.pose=pose _waypoint.set_cartesian_pose(poseStamped, self._tip_name, []) self._motion_trajectory.append_waypoint(_waypoint.to_msg()) # # run motion... self._light.head_green() result=self._motion_trajectory.send_trajectory( wait_for_result=wait_for_result,timeout=tout) # if result is None: self._light.head_yellow() print("Trajectory FAILED to send") return None # if not wait_for_result : return True # if result.result: self._light.head_on() else: self._light.head_red() # self._motion_trajectory=None return result.result
def map_keyboard(side): limb = intera_interface.Limb(side) tip_name = 'right_hand' try: gripper = intera_interface.Gripper(side + '_gripper') except: has_gripper = False rospy.loginfo("The electric gripper is not detected on the robot.") else: has_gripper = True joints = limb.joint_names() #得到所有关节名字,变量为列表 traj_options = TrajectoryOptions() traj_options.interpolation_type = 'JOINT' traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) _max_joint_speed_ratio = 0.2 _max_joint_accel = 0.2 wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=_max_joint_speed_ratio, max_joint_accel=_max_joint_accel) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) def set_j(limb, joint_name, delta): # 关节移动 traj_options.interpolation_type = 'JOINT' traj.set_trajectory_options(trajectory_options = traj_options) current_position = limb.joint_ordered_angles() #获取当前关节角度 # 将需要移动的关节角度增减 current_position[joints.index(joint_name)] = current_position[joints.index(joint_name)] + delta wpt_opts1 = MotionWaypointOptions(max_joint_speed_ratio=_max_joint_speed_ratio, max_joint_accel=_max_joint_accel) waypoint.set_waypoint_options(wpt_opts1) waypoint.set_joint_angles(current_position) traj.clear_waypoints() traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory() if result is None: rospy.logerr('Trajectory FAILED to send') if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) limb.exit_control_mode() # limb.set_joint_positions(joint_command) traj.clear_waypoints() def set_l(limb, cartesian_axis ,distance): traj_options.interpolation_type = 'CARTESIAN' traj.set_trajectory_options(trajectory_options = traj_options) endpoint_state = limb.tip_state(tip_name) if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', tip_name) return None pose = endpoint_state.pose if cartesian_axis == 'x': pose.position.x += distance elif cartesian_axis == 'y': pose.position.y += distance elif cartesian_axis == 'z': pose.position.z += distance poseStamped = PoseStamped() poseStamped.pose = pose joint_angles = limb.joint_ordered_angles() wpt_opts2 = MotionWaypointOptions(max_joint_speed_ratio=_max_joint_speed_ratio, max_joint_accel=_max_joint_accel) waypoint.set_waypoint_options(wpt_opts2) waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) traj.clear_waypoints() traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory() if result is None: rospy.logerr('Trajectory FAILED to send') if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) limb.exit_control_mode() traj.clear_waypoints() def set_g(action): if has_gripper: print('griper ok. ') if action == "close": gripper.close() elif action == "open": gripper.open() elif action == "calibrate": gripper.calibrate() bindings = { '1': (set_j, [limb, joints[0], 0.1], joints[0]+" increase"), 'q': (set_j, [limb, joints[0], -0.1], joints[0]+" decrease"), '2': (set_j, [limb, joints[1], 0.1], joints[1]+" increase"), 'w': (set_j, [limb, joints[1], -0.1], joints[1]+" decrease"), '3': (set_j, [limb, joints[2], 0.1], joints[2]+" increase"), 'e': (set_j, [limb, joints[2], -0.1], joints[2]+" decrease"), '4': (set_j, [limb, joints[3], 0.1], joints[3]+" increase"), 'r': (set_j, [limb, joints[3], -0.1], joints[3]+" decrease"), '5': (set_j, [limb, joints[4], 0.1], joints[4]+" increase"), 't': (set_j, [limb, joints[4], -0.1], joints[4]+" decrease"), '6': (set_j, [limb, joints[5], 0.1], joints[5]+" increase"), 'y': (set_j, [limb, joints[5], -0.1], joints[5]+" decrease"), '7': (set_j, [limb, joints[6], 0.1], joints[6]+" increase"), 'u': (set_j, [limb, joints[6], -0.1], joints[6]+" decrease"), 'a': (set_l, [limb, "x", +0.1], " x" + " increase"), 'z': (set_l, [limb, "x", -0.1], " x" + " decrease"), 's': (set_l, [limb, "y", +0.1], " y" + " increase"), 'x': (set_l, [limb, "y", -0.1], " y" + " decrease"), 'd': (set_l, [limb, "z", +0.1], " z" + " increase"), 'c': (set_l, [limb, "z", -0.1], " z" + " decrease"), } if has_gripper: bindings.update({ '8': (set_g, "close", side+" gripper close"), 'i': (set_g, "open", side+" gripper open"), '9': (set_g, "calibrate", side+" gripper calibrate") }) done = False print("Controlling joints. Press ? for help, Esc to quit.") time_tamp = None time_label = None while not done and not rospy.is_shutdown(): c = intera_external_devices.getch() if c: #catch Esc or ctrl-c if c in ['\x1b', '\x03']: done = True rospy.signal_shutdown("Example finished.") elif c == '\\': set_speed = input('请输入设定的速度,按下Enter确认。\n') _max_joint_speed_ratio= set_speed elif c in bindings: cmd = bindings[c] if c == '8' or c == 'i' or c == '9': cmd[0](cmd[1]) print("command: %s" % (cmd[2],)) else: #expand binding to something like "set_j(right, 'j0', 0.1)" cmd[0](*cmd[1]) print("command: %s" % (cmd[2],)) else: print("key bindings: ") print(" Esc: Quit") print(" ?: Help") for key, val in sorted(bindings.items(), key=lambda x: x[1][2]): print(" %s: %s" % (key, val[2])) time_tamp = rospy.get_time() else: if (time_tamp is not None) : if time_tamp != time_label : if (rospy.get_time() - time_tamp) > 1 : print ('当前姿态:') print (limb.tip_state(tip_name).pose) # print (limb.tip_state(tip_name).pose.position) # print (limb.tip_state(tip_name).pose.position.x) # print (limb.tip_state(tip_name).pose.orientation) # print (limb.endpoint_pose()) # print (limb.endpoint_pose()['position']) # print (limb.endpoint_pose()['orientation']) print ('当前关节角:') print (limb.joint_angles()) print ('\n') time_label = time_tamp traj.stop_trajectory()
def move2cartesian(position=None, orientation=None, relative_pose=None, in_tip_frame=False, joint_angles=[], tip_name='right_hand', linear_speed=0.6, linear_accel=0.6, rotational_speed=1.57, rotational_accel=1.57, timeout=None, neutral=False): """ Move the robot arm to the specified configuration. Call using: $ rosrun intera_examples go_to_cartesian_pose.py [arguments: see below] -p 0.4 -0.3 0.18 -o 0.0 1.0 0.0 0.0 -t right_hand --> Go to position: x=0.4, y=-0.3, z=0.18 meters --> with quaternion orientation (0, 1, 0, 0) and tip name right_hand --> The current position or orientation will be used if only one is provided. -q 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 --> Go to joint angles: 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 using default settings --> If a Cartesian pose is not provided, Forward kinematics will be used --> If a Cartesian pose is provided, the joint angles will be used to bias the nullspace -R 0.01 0.02 0.03 0.1 0.2 0.3 -T -> Jog arm with Relative Pose (in tip frame) -> x=0.01, y=0.02, z=0.03 meters, roll=0.1, pitch=0.2, yaw=0.3 radians -> The fixed position and orientation paramters will be ignored if provided """ try: #rospy.init_node('go_to_cartesian_pose_py') limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options = traj_options, limb = limb) wpt_opts = MotionWaypointOptions(max_linear_speed=linear_speed, max_linear_accel=linear_accel, max_rotational_speed=rotational_speed, max_rotational_accel=rotational_accel, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) joint_names = limb.joint_names() if joint_angles and len(joint_angles) != len(joint_names): rospy.logerr('len(joint_angles) does not match len(joint_names!)') return None if neutral == True: limb.move_to_neutral() else: if (position is None and orientation is None and relative_pose is None): if joint_angles: # does Forward Kinematics waypoint.set_joint_angles(joint_angles, tip_name, joint_names) else: rospy.loginfo("No Cartesian pose or joint angles given. Using default") waypoint.set_joint_angles(joint_angles=None, active_endpoint=tip_name) else: endpoint_state = limb.tip_state(tip_name) if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', tip_name) return None pose = endpoint_state.pose if relative_pose is not None: if len(relative_pose) != 6: rospy.logerr('Relative pose needs to have 6 elements (x,y,z,roll,pitch,yaw)') return None # create kdl frame from relative pose rot = PyKDL.Rotation.RPY(relative_pose[3], relative_pose[4], relative_pose[5]) trans = PyKDL.Vector(relative_pose[0], relative_pose[1], relative_pose[2]) f2 = PyKDL.Frame(rot, trans) # and convert the result back to a pose message if in_tip_frame: # end effector frame pose = posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base frame pose = posemath.toMsg(f2 * posemath.fromMsg(pose)) else: if position is not None and len(position) == 3: pose.position.x = position[0] pose.position.y = position[1] pose.position.z = position[2] if orientation is not None and len(orientation) == 4: pose.orientation.x = orientation[0] pose.orientation.y = orientation[1] pose.orientation.z = orientation[2] pose.orientation.w = orientation[3] poseStamped = PoseStamped() poseStamped.pose = pose if not joint_angles: # using current joint angles for nullspace bais if not provided joint_angles = limb.joint_ordered_angles() waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) else: waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=timeout) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. Exiting before trajectory completion.')
def interaction_joint_trajectory( limb, joint_angles, trajType, interaction_active, interaction_control_mode, interaction_frame, speed_ratio, accel_ratio, K_impedance, max_impedance, in_endpoint_frame, force_command, K_nullspace, endpoint_name, timeout, disable_damping_in_force_control, disable_reference_resetting, rotations_for_constrained_zeroG): try: traj = MotionTrajectory(limb=limb) wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=speed_ratio, max_joint_accel=accel_ratio) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) # one single waypoint current_joint_angles = limb.joint_ordered_angles() waypoint.set_joint_angles(joint_angles=current_joint_angles) traj.append_waypoint(waypoint.to_msg()) if len(current_joint_angles) != len(joint_angles): rospy.logerr('The number of joint_angles must be %d', len(current_joint_angles)) return None # ----- testing intermediate points with real robot middle_joint_angles = [ (current_joint_angles[i] + joint_angles[i]) / 2.0 for i in xrange(len(current_joint_angles)) ] waypoint.set_joint_angles(joint_angles=middle_joint_angles) traj.append_waypoint(waypoint.to_msg()) waypoint.set_joint_angles(joint_angles=joint_angles) traj.append_waypoint(waypoint.to_msg()) # ----- end testing intermediate points with real robot # set the interaction control options in the current configuration interaction_options = InteractionOptions() trajectory_options = TrajectoryOptions() trajectory_options.interaction_control = True trajectory_options.interpolation_type = trajType interaction_options.set_interaction_control_active( int2bool(interaction_active)) interaction_options.set_K_impedance(K_impedance) interaction_options.set_max_impedance(int2bool(max_impedance)) interaction_options.set_interaction_control_mode( interaction_control_mode) interaction_options.set_in_endpoint_frame(int2bool(in_endpoint_frame)) interaction_options.set_force_command(force_command) interaction_options.set_K_nullspace(K_nullspace) interaction_options.set_endpoint_name(endpoint_name) if len(interaction_frame) < 7: rospy.logerr('The number of elements must be 7!') elif len(interaction_frame) == 7: quat_sum_square = interaction_frame[3] * interaction_frame[ 3] + interaction_frame[4] * interaction_frame[ 4] + interaction_frame[5] * interaction_frame[ 5] + interaction_frame[6] * interaction_frame[6] if quat_sum_square < 1.0 + 1e-7 and quat_sum_square > 1.0 - 1e-7: target_interaction_frame = Pose() target_interaction_frame.position.x = interaction_frame[0] target_interaction_frame.position.y = interaction_frame[1] target_interaction_frame.position.z = interaction_frame[2] target_interaction_frame.orientation.w = interaction_frame[3] target_interaction_frame.orientation.x = interaction_frame[4] target_interaction_frame.orientation.y = interaction_frame[5] target_interaction_frame.orientation.z = interaction_frame[6] interaction_options.set_interaction_frame( target_interaction_frame) else: rospy.logerr( 'Invalid input to quaternion! The quaternion must be a unit quaternion!' ) else: rospy.logerr('Invalid input to interaction_frame!') interaction_options.set_disable_damping_in_force_control( disable_damping_in_force_control) interaction_options.set_disable_reference_resetting( disable_reference_resetting) interaction_options.set_rotations_for_constrained_zeroG( rotations_for_constrained_zeroG) trajectory_options.interaction_params = interaction_options.to_msg() traj.set_trajectory_options(trajectory_options) result = traj.send_trajectory(timeout=timeout) if result is None: rospy.logerr('Trajectory FAILED to send!') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory with interaction options set!' ) else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) # print the resultant interaction options rospy.loginfo('Interaction Options:\n%s', interaction_options.to_msg()) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. %s', 'Exiting before trajectory completion.')
from intera_motion_msgs.msg import TrajectoryOptions from geometry_msgs.msg import (Pose, PoseStamped) import tf from intera_interface import Limb rospy.init_node('sawyer_moveit_from_topic_irl', anonymous=True) limb = Limb() wpt_opts = MotionWaypointOptions(max_linear_speed=5.0, max_linear_accel=5.0, max_rotational_speed=5.0, max_rotational_accel=5.0, max_joint_speed_ratio=1.0) traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN listener = tf.TransformListener() BASE_X = 0.5 BASE_Y = -0.3 BASE_Z = 0.2 OR_X = 1.0 OR_Y = 0.0 OR_Z = 0.0 OR_W = 0.0 SCALING = 0.3 pose_goal = Pose()
def cartesian_pose(args): """ Move the robot arm to the specified configuration. Call using: $ rosrun intera_examples go_to_cartesian_pose.py [arguments: see below] -p 0.4 -0.3 0.18 -o 0.0 1.0 0.0 0.0 -t right_hand --> Go to position: x=0.4, y=-0.3, z=0.18 meters --> with quaternion orientation (0, 1, 0, 0) and tip name right_hand --> The current position or orientation will be used if only one is provided. -q 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 --> Go to joint angles: 0.0 -0.9 0.0 1.8 0.0 -0.9 0.0 using default settings --> If a Cartesian pose is not provided, Forward kinematics will be used --> If a Cartesian pose is provided, the joint angles will be used to bias the nullspace -R 0.01 0.02 0.03 0.1 0.2 0.3 -T -> Jog arm with Relative Pose (in tip frame) -> x=0.01, y=0.02, z=0.03 meters, roll=0.1, pitch=0.2, yaw=0.3 radians -> The fixed position and orientation paramters will be ignored if provided arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description="cartesian_pose.__doc__") parser.add_argument( "-p", "--position", type=float, nargs='+', help="Desired end position: X, Y, Z") parser.add_argument( "-o", "--orientation", type=float, nargs='+', help="Orientation as a quaternion (x, y, z, w)") parser.add_argument( "-R", "--relative_pose", type=float, nargs='+', help="Jog pose by a relative amount in the base frame: X, Y, Z, roll, pitch, yaw") parser.add_argument( "-T", "--in_tip_frame", action='store_true', help="For relative jogs, job in tip frame (default is base frame)") parser.add_argument( "-q", "--joint_angles", type=float, nargs='+', default=[], help="A list of joint angles, one for each of the 7 joints, J0...J6") parser.add_argument( "-t", "--tip_name", default='right_hand', help="The tip name used by the Cartesian pose") parser.add_argument( "--linear_speed", type=float, default=0.6, help="The max linear speed of the endpoint (m/s)") parser.add_argument( "--linear_accel", type=float, default=0.6, help="The max linear acceleration of the endpoint (m/s/s)") parser.add_argument( "--rotational_speed", type=float, default=1.57, help="The max rotational speed of the endpoint (rad/s)") parser.add_argument( "--rotational_accel", type=float, default=1.57, help="The max rotational acceleration of the endpoint (rad/s/s)") parser.add_argument( "--timeout", type=float, default=None, help="Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout.") """ try: #rospy.init_node('go_to_cartesian_pose_py') limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions( max_linear_speed=args.linear_speed, max_linear_accel=args.linear_accel, max_rotational_speed=args.rotational_speed, max_rotational_accel=args.rotational_accel, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() if args.joint_angles and len(args.joint_angles) != len(joint_names): rospy.logerr('len(joint_angles) does not match len(joint_names!)') return None if (args.position is None and args.orientation is None and args.relative_pose is None): if args.joint_angles: # does Forward Kinematics waypoint.set_joint_angles(args.joint_angles, args.tip_name, joint_names) else: rospy.loginfo( "No Cartesian pose or joint angles given. Using default") waypoint.set_joint_angles(joint_angles=None, active_endpoint=args.tip_name) else: endpoint_state = limb.tip_state(args.tip_name) if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', args.tip_name) return None pose = endpoint_state.pose if args.relative_pose is not None: if len(args.relative_pose) != 6: rospy.logerr( 'Relative pose needs to have 6 elements (x,y,z,roll,pitch,yaw)' ) return None # create kdl frame from relative pose rot = PyKDL.Rotation.RPY(args.relative_pose[3], args.relative_pose[4], args.relative_pose[5]) trans = PyKDL.Vector(args.relative_pose[0], args.relative_pose[1], args.relative_pose[2]) f2 = PyKDL.Frame(rot, trans) # and convert the result back to a pose message if args.in_tip_frame: # end effector frame pose = posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base frame pose = posemath.toMsg(f2 * posemath.fromMsg(pose)) else: if args.position is not None and len(args.position) == 3: pose.position.x = args.position[0] pose.position.y = args.position[1] pose.position.z = args.position[2] if args.orientation is not None and len(args.orientation) == 4: pose.orientation.x = args.orientation[0] pose.orientation.y = args.orientation[1] pose.orientation.z = args.orientation[2] pose.orientation.w = args.orientation[3] poseStamped = PoseStamped() poseStamped.pose = pose waypoint.set_cartesian_pose(poseStamped, args.tip_name, args.joint_angles) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=args.timeout) if result is None: rospy.logerr('Trajectory FAILED to send') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!') else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr( 'Keyboard interrupt detected from the user. Exiting before trajectory completion.' )
def go_to_cartesian(position=None, orientation=None, joint_angles=None, linear_speed=0.1, rotational_speed=0.57, linear_accel=0.3, tip_name='right_hand', relative_pose=None, rotational_accel=0.57, timeout=None): if not rospy.is_shutdown(): try: limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions( max_linear_speed=linear_speed, max_linear_accel=linear_accel, max_rotational_speed=rotational_speed, max_rotational_accel=rotational_accel, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_names = limb.joint_names() if joint_angles and len(joint_angles) != len(joint_names): rospy.logerr( 'len(joint_angles) does not match len(joint_names!)') return None if (position is None and orientation is None and relative_pose is None): if joint_angles: # does Forward Kinematics waypoint.set_joint_angles(joint_angles, tip_name, joint_names) else: rospy.loginfo( "No Cartesian pose or joint angles given. Using default" ) waypoint.set_joint_angles(joint_angles=None, active_endpoint=tip_name) else: endpoint_state = limb.tip_state(tip_name) if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', tip_name) return None pose = endpoint_state.pose if relative_pose is not None: if len(relative_pose) != 6: rospy.logerr( 'Relative pose needs to have 6 elements (x,y,z,roll,pitch,yaw)' ) return None # create kdl frame from relative pose rot = PyKDL.Rotation.RPY(relative_pose[3], relative_pose[4], relative_pose[5]) trans = PyKDL.Vector(relative_pose[0], relative_pose[1], relative_pose[2]) f2 = PyKDL.Frame(rot, trans) # and convert the result back to a pose message if in_tip_frame: # end effector frame pose = posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base frame pose = posemath.toMsg(f2 * posemath.fromMsg(pose)) else: if position is not None: pose.position.x = position.x pose.position.y = position.y pose.position.z = position.z if orientation is not None: pose.orientation.x = orientation.x pose.orientation.y = orientation.y pose.orientation.z = orientation.z pose.orientation.w = orientation.w poseStamped = PoseStamped() poseStamped.pose = pose waypoint.set_cartesian_pose(poseStamped, tip_name, joint_angles) #rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=timeout) if result is None: return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!') else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr( 'Keyboard interrupt detected from the user. Exiting before trajectory completion.' )
def moveTo(myArgs): arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main_server.__doc__) parser.add_argument( "-p", "--position", type=float, nargs='+', help="Desired end position: X, Y, Z") parser.add_argument( "-o", "--orientation", type=float, nargs='+', help="Orientation as a quaternion (x, y, z, w)") parser.add_argument( "-R", "--relative_pose", type=float, nargs='+', help="Jog pose by a relative amount in the base frame: X, Y, Z, roll, pitch, yaw") parser.add_argument( "-T", "--in_tip_frame", action='store_true', help="For relative jogs, job in tip frame (default is base frame)") parser.add_argument( "-q", "--joint_angles", type=float, nargs='+', default=[], help="A list of joint angles, one for each of the 7 joints, J0...J6") parser.add_argument( "--timeout", type=float, default=None, help="Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout.") args = parser.parse_args(myArgs.call.split(" ")) print(args.position) #test_string = ['-p','0.5', '0.3', '0.5'] #args = parser.parse_args(test_string) try: limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options = traj_options, limb = limb) wpt_opts = MotionWaypointOptions(max_linear_speed=0.4, max_linear_accel=0.4, max_rotational_speed=1.57, max_rotational_accel=1.5, max_joint_speed_ratio=1.0) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) joint_names = limb.joint_names() if args.joint_angles and len(args.joint_angles) != len(joint_names): rospy.logerr('len(joint_angles) does not match len(joint_names!)') return "failed" if (args.position is None and args.orientation is None and args.relative_pose is None): if args.joint_angles: # does Forward Kinematics waypoint.set_joint_angles(args.joint_angles,'right_hand', joint_names) else: rospy.loginfo("No Cartesian pose or joint angles given. Using default") waypoint.set_joint_angles(joint_angles=None, active_endpoint='right_hand') else: endpoint_state = limb.tip_state('right_hand') if endpoint_state is None: rospy.logerr('Endpoint state not found with tip name %s', 'right_hand') return "failed" pose = endpoint_state.pose if args.relative_pose is not None: if len(args.relative_pose) != 6: rospy.logerr('Relative pose needs to have 6 elements (x,y,z,roll,pitch,yaw)') return "failed" # create kdl frame from relative pose rot = PyKDL.Rotation.RPY(args.relative_pose[3], args.relative_pose[4], args.relative_pose[5]) trans = PyKDL.Vector(args.relative_pose[0], args.relative_pose[1], args.relative_pose[2]) f2 = PyKDL.Frame(rot, trans) # and convert the result back to a pose message if args.in_tip_frame: # end effector frame pose = posemath.toMsg(posemath.fromMsg(pose) * f2) else: # base frame pose = posemath.toMsg(f2 * posemath.fromMsg(pose)) else: if args.position is not None and len(args.position) == 3: pose.position.x = args.position[0] pose.position.y = args.position[1] pose.position.z = args.position[2] if args.orientation is not None and len(args.orientation) == 4: pose.orientation.x = args.orientation[0] pose.orientation.y = args.orientation[1] pose.orientation.z = args.orientation[2] pose.orientation.w = args.orientation[3] poseStamped = PoseStamped() poseStamped.pose = pose waypoint.set_cartesian_pose(poseStamped, 'right_hand', args.joint_angles) rospy.loginfo('Sending waypoint: \n%s', waypoint.to_string()) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=args.timeout) if result is None: rospy.logerr('Trajectory FAILED to send') return 'Trajectory FAILED to send' if result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') return 'Motion Success' else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) return result.errorId except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. Exiting before trajectory completion.') return "failed"
def main(): """ Send a random-walk trajectory, starting from the current pose of the robot. Can be used to send both joint and cartesian trajectories. WARNING: Make sure the surrounding area around the robot is collision free prior to sending random trajectories. Call using: $ rosrun intera_examples send_random_trajectory.py [arguments: see below] -n 5 -t JOINT -s 0.5 --> Send a trandom joint trajectory with 5 waypoints, using a speed ratio of 0.5 for all waypoints. Use default random walk settings. -d 0.1 -b 0.2 --> Send a random trajectory with default trajectory settings. Use a maximum step distance of 0.1*(upper joint limit - lower joint limit) and avoid the upper and lower joint limits by a boundary of 0.2*(upper joint limit - lower joint limit). -o ~/Desktop/fileName.bag --> Save the trajectory message to a bag file -p --> Prints the trajectory to terminal before sending """ arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__doc__) parser.add_argument( "-n", "--waypoint_count", type=int, default=5, help="number of waypoints to include in the trajectory") parser.add_argument( "-d", "--stepDistance", type=float, default=0.05, help="normalized random walk step distance") parser.add_argument( "-b", "--boundaryPadding", type=float, default=0.1, help="normalized padding to apply to joint limits") parser.add_argument( "-t", "--trajType", type=str, default='JOINT', choices=['JOINT', 'CARTESIAN'], help="trajectory interpolation type") parser.add_argument( "-s", "--speed_ratio", type=float, default=0.5, help="A value between 0.0 (slow) and 1.0 (fast)") parser.add_argument( "-a", "--accel_ratio", type=float, default=0.5, help="A value between 0.0 (slow) and 1.0 (fast)") parser.add_argument( "-o", "--output_file", help="Save the trajectory task to a bag file") parser.add_argument( "--output_file_type", default="yaml", choices=["csv", "yaml"], help="Select the save file type") parser.add_argument( "-p", "--print_trajectory", action='store_true', default=False, help="print the trajectory after loading") parser.add_argument( "--do_not_send", action='store_true', default=False, help="generate the trajectory, but do not send to motion controller.") parser.add_argument( "--log_file_output", help="Save motion controller log messages to this file name") parser.add_argument( "--timeout", type=float, default=None, help="Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout.") args = parser.parse_args() if args.waypoint_count < 1: args.waypoint_count = 1 rospy.logwarn('Input out of bounds! Setting waypoint_count = 1') try: rospy.init_node('send_random_joint_trajectory_py') if not args.do_not_send: rospy.logwarn('Make sure the surrounding area around the robot is ' 'collision free prior to sending random trajectories.') k = input("Press 'Enter' when the robot is clear to continue...") if k: rospy.logerr("Please press only the 'Enter' key to begin execution. Exiting...") sys.exit(1) # Set the trajectory options limb = Limb() traj_opts = TrajectoryOptions() traj_opts.interpolation_type = args.trajType traj = MotionTrajectory(trajectory_options = traj_opts, limb = limb) # Set the waypoint options wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=args.speed_ratio, max_joint_accel=args.accel_ratio) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) # Append a waypoint at the current pose waypoint.set_joint_angles(limb.joint_ordered_angles()) traj.append_waypoint(waypoint.to_msg()) # Set up the random walk generator walk = RandomWalk() limits = JointLimits() walk.set_lower_limits(limits.get_joint_lower_limits(limb.joint_names())) walk.set_upper_limits(limits.get_joint_upper_limits(limb.joint_names())) walk.set_last_point(waypoint.get_joint_angles()) walk.set_boundary_padding(args.boundaryPadding) walk.set_maximum_distance(args.stepDistance) for i in range(0, args.waypoint_count): joint_angles = walk.get_next_point() waypoint.set_joint_angles(joint_angles = joint_angles) traj.append_waypoint(waypoint.to_msg()) if args.output_file is not None: if args.output_file_type == "csv": traj.to_csv_file(args.output_file) elif args.output_file_type == "yaml": traj.to_yaml_file(args.output_file) else: rospy.logwarn("Did not recognize output file type") if args.print_trajectory: rospy.loginfo('\n' + traj.to_string()) if args.log_file_output is not None: traj.set_log_file_name(args.log_file_output) if not args.do_not_send: result = traj.send_trajectory(timeout=args.timeout) if result is None: rospy.logerr('Trajectory FAILED to send') elif result.result: rospy.loginfo('Motion controller successfully finished the trajectory!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. ' 'Exiting before trajectory completion.')
def joint_angles_in_contact(input_arg): """ Move the robot arm to the specified configuration with the desired interaction control options. Call using: $ rosrun intera_examples go_to_joint_angles_in_contact.py [arguments: see below] -q 0.0 0.0 0.0 0.0 0.0 0.0 0.0 --> Go to joint pose: 0.0 0.0 0.0 0.0 0.0 0.0 0.0 using default settings -q 0.1 -0.2 0.15 -0.05 -0.08 0.14 -0.04 -s 0.1 --> Go to pose [...] with a speed ratio of 0.1 -q -0.2 0.1 0.1 0.2 -0.3 0.2 0.4 -s 0.9 -a 0.1 --> Go to pose [...] witha speed ratio of 0.9 and an accel ratio of 0.1 --trajType CARTESIAN --> Use a Cartesian interpolated endpoint path to reach the goal === Interaction Mode options === -st 1 --> Set the interaction controller state (1 for True, 0 for False) in the current configuration -k 500.0 500.0 500.0 10.0 10.0 10.0 --> Set K_impedance to [500.0 500.0 500.0 10.0 10.0 10.0] in the current configuration -m 0 --> Set max_impedance to False for all 6 directions in the current configuration -m 1 1 0 1 1 1 --> Set max_impedance to [True True False True True True] in the current configuration -kn 5.0 3.0 5.0 4.0 6.0 4.0 6.0 --> Set K_nullspace to [5.0 3.0 5.0 4.0 6.0 4.0 6.0] in the current configuration -f 0.0 0.0 30.0 0.0 0.0 0.0 --> Set force_command to [0.0 0.0 30.0 0.0 0.0 0.0] in the current configuration -ef --> Set in_endpoint_frame to True in the current configuration -en 'right_hand' --> Specify the desired endpoint frame where impedance and force control behaviors are defined -md 1 --> Set interaction_control_mode to impedance mode for all 6 directions in the current configuration (1: impedance, 2: force, 3: impedance with force limit, 4: force with motion limit) -md 1 1 2 1 1 1 --> Set interaction_control_mode to [impedance, impedance, force, impedance, impedance, impedance] in the current configuration (1: impedance, 2: force, 3: impedance with force limit, 4: force with motion limit) """ arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser( formatter_class=arg_fmt, description="joint_angles_in_contact.__doc__") parser.add_argument( "-q", "--joint_angles", type=float, nargs='+', default=[0.0, -0.9, 0.0, 1.8, 0.0, -0.9, 0.0], help="A list of joint angles, one for each of the 7 joints, J0...J6") parser.add_argument( "-s", "--speed_ratio", type=float, default=0.1, help="A value between 0.001 (slow) and 1.0 (maximum joint velocity)") parser.add_argument( "-a", "--accel_ratio", type=float, default=0.5, help="A value between 0.001 (slow) and 1.0 (maximum joint accel)") parser.add_argument("-t", "--trajType", type=str, default='JOINT', choices=['JOINT', 'CARTESIAN'], help="trajectory interpolation type") parser.add_argument( "-st", "--interaction_active", type=int, default=1, choices=[0, 1], help="Activate (1) or Deactivate (0) interaction controller") parser.add_argument( "-k", "--K_impedance", type=float, nargs='+', default=[1300.0, 1300.0, 1300.0, 30.0, 30.0, 30.0], help= "A list of desired stiffnesses, one for each of the 6 directions -- stiffness units are (N/m) for first 3 and (Nm/rad) for second 3 values" ) parser.add_argument( "-m", "--max_impedance", type=int, nargs='+', default=[1, 1, 1, 1, 1, 1], choices=[0, 1], help= "A list of impedance modulation state, one for each of the 6 directions (a single value can be provided to apply the same value to all the directions) -- 0 for False, 1 for True" ) parser.add_argument( "-md", "--interaction_control_mode", type=int, nargs='+', default=[1, 1, 1, 1, 1, 1], choices=[1, 2, 3, 4], help= "A list of desired interaction control mode (1: impedance, 2: force, 3: impedance with force limit, 4: force with motion limit), one for each of the 6 directions" ) parser.add_argument( "-fr", "--interaction_frame", type=float, nargs='+', default=[0, 0, 0, 1, 0, 0, 0], help= "Specify the reference frame for the interaction controller -- first 3 values are positions [m] and last 4 values are orientation in quaternion (w, x, y, z)" ) parser.add_argument( "-ef", "--in_endpoint_frame", action='store_true', default=False, help= "Set the desired reference frame to endpoint frame; otherwise, it is base frame by default" ) parser.add_argument( "-en", "--endpoint_name", type=str, default='right_hand', help= "Set the desired endpoint frame by its name; otherwise, it is right_hand frame by default" ) parser.add_argument( "-f", "--force_command", type=float, nargs='+', default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], help= "A list of desired force commands, one for each of the 6 directions -- in force control mode this is the vector of desired forces/torques to be regulated in (N) and (Nm), in impedance with force limit mode this vector specifies the magnitude of forces/torques (N and Nm) that the command will not exceed" ) parser.add_argument( "-kn", "--K_nullspace", type=float, nargs='+', default=[5.0, 10.0, 5.0, 10.0, 5.0, 10.0, 5.0], help= "A list of desired nullspace stiffnesses, one for each of the 7 joints (a single value can be provided to apply the same value to all the directions) -- units are in (Nm/rad)" ) parser.add_argument("-dd", "--disable_damping_in_force_control", action='store_true', default=False, help="Disable damping in force control") parser.add_argument( "-dr", "--disable_reference_resetting", action='store_true', default=False, help= "The reference signal is reset to actual position to avoid jerks/jumps when interaction parameters are changed. This option allows the user to disable this feature." ) parser.add_argument( "-rc", "--rotations_for_constrained_zeroG", action='store_true', default=False, help= "Allow arbitrary rotational displacements from the current orientation for constrained zero-G (use only for a stationary reference orientation)" ) parser.add_argument( "--timeout", type=float, default=None, help= "Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout." ) args = parser.parse_args(input_arg[1:]) try: #rospy.init_node('go_to_joint_angles_in_contact_py') limb = Limb() traj = MotionTrajectory(limb=limb) wpt_opts = MotionWaypointOptions( max_joint_speed_ratio=args.speed_ratio, max_joint_accel=args.accel_ratio) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) joint_angles = limb.joint_ordered_angles() waypoint.set_joint_angles(joint_angles=joint_angles) traj.append_waypoint(waypoint.to_msg()) if len(args.joint_angles) != len(joint_angles): rospy.logerr('The number of joint_angles must be %d', len(joint_angles)) return None waypoint.set_joint_angles(joint_angles=args.joint_angles) traj.append_waypoint(waypoint.to_msg()) # set the interaction control options in the current configuration interaction_options = InteractionOptions() trajectory_options = TrajectoryOptions() trajectory_options.interaction_control = True trajectory_options.interpolation_type = args.trajType interaction_options.set_interaction_control_active( int2bool(args.interaction_active)) interaction_options.set_K_impedance(args.K_impedance) interaction_options.set_max_impedance(int2bool(args.max_impedance)) interaction_options.set_interaction_control_mode( args.interaction_control_mode) interaction_options.set_in_endpoint_frame( int2bool(args.in_endpoint_frame)) interaction_options.set_force_command(args.force_command) interaction_options.set_K_nullspace(args.K_nullspace) interaction_options.set_endpoint_name(args.endpoint_name) if len(args.interaction_frame) < 7: rospy.logerr('The number of elements must be 7!') elif len(args.interaction_frame) == 7: quat_sum_square = args.interaction_frame[ 3] * args.interaction_frame[3] + args.interaction_frame[ 4] * args.interaction_frame[4] +args.interaction_frame[5] * args.interaction_frame[ 5] + args.interaction_frame[6] * args.interaction_frame[6] if quat_sum_square < 1.0 + 1e-7 and quat_sum_square > 1.0 - 1e-7: interaction_frame = Pose() interaction_frame.position.x = args.interaction_frame[0] interaction_frame.position.y = args.interaction_frame[1] interaction_frame.position.z = args.interaction_frame[2] interaction_frame.orientation.w = args.interaction_frame[3] interaction_frame.orientation.x = args.interaction_frame[4] interaction_frame.orientation.y = args.interaction_frame[5] interaction_frame.orientation.z = args.interaction_frame[6] interaction_options.set_interaction_frame(interaction_frame) else: rospy.logerr( 'Invalid input to quaternion! The quaternion must be a unit quaternion!' ) else: rospy.logerr('Invalid input to interaction_frame!') interaction_options.set_disable_damping_in_force_control( args.disable_damping_in_force_control) interaction_options.set_disable_reference_resetting( args.disable_reference_resetting) interaction_options.set_rotations_for_constrained_zeroG( args.rotations_for_constrained_zeroG) trajectory_options.interaction_params = interaction_options.to_msg() traj.set_trajectory_options(trajectory_options) result = traj.send_trajectory(timeout=args.timeout) if result is None: rospy.logerr('Trajectory FAILED to send!') return if result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory with interaction options set!' ) return True else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) # print the resultant interaction options rospy.loginfo('Interaction Options:\n%s', interaction_options.to_msg()) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. %s', 'Exiting before trajectory completion.')
def main(): arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__doc__) ##### parser.add_argument( "-p", "--position", type=float, nargs='+', default=[0, 0, 0], help="Desired end position: X, Y, Z") parser.add_argument( "-o", "--orientation", type=float, nargs='+', default=[0.704020578925, 0.710172716916, 0.00244101361829, 0.00194372088834], help="Orientation as a quaternion (x, y, z, w)") ##### parser.add_argument( "-q", "--joint_angles", type=float, nargs='+', default=[0.0, -0.9, 0.0, 1.8, 0.0, -0.9, 0.0], help="A list of joint angles, one for each of the 7 joints, J0...J6") parser.add_argument( "-s", "--speed_ratio", type=float, default=0.2, help="A value between 0.001 (slow) and 1.0 (maximum joint velocity)") parser.add_argument( "-a", "--accel_ratio", type=float, default=0.05, help="A value between 0.001 (slow) and 1.0 (maximum joint accel)") parser.add_argument( "-t", "--trajType", type=str, default='JOINT', choices=['JOINT', 'CARTESIAN'], help="trajectory interpolation type") parser.add_argument( "-st", "--interaction_active", type=int, default=1, choices = [0, 1], help="Activate (1) or Deactivate (0) interaction controller") parser.add_argument( "-k", "--K_impedance", type=float, nargs='+', default=[1300.0, 1300.0, 1300.0, 30.0, 30.0, 30.0], help="A list of desired stiffnesses, one for each of the 6 directions -- stiffness units are (N/m) for first 3 and (Nm/rad) for second 3 values") parser.add_argument( "-m", "--max_impedance", type=int, nargs='+', default=[1, 1, 1, 1, 1, 1], choices = [0, 1], help="A list of impedance modulation state, one for each of the 6 directions (a single value can be provided to apply the same value to all the directions) -- 0 for False, 1 for True") parser.add_argument( "-md", "--interaction_control_mode", type=int, nargs='+', default=[1, 1, 1, 1, 1, 1], choices = [1,2,3,4], help="A list of desired interaction control mode (1: impedance, 2: force, 3: impedance with force limit, 4: force with motion limit), one for each of the 6 directions") parser.add_argument( "-fr", "--interaction_frame", type=float, nargs='+', default=[0, 0, 0, 1, 0, 0, 0], help="Specify the reference frame for the interaction controller -- first 3 values are positions [m] and last 4 values are orientation in quaternion (w, x, y, z)") parser.add_argument( "-ef", "--in_endpoint_frame", action='store_true', default=False, help="Set the desired reference frame to endpoint frame; otherwise, it is base frame by default") parser.add_argument( "-en", "--endpoint_name", type=str, default='right_hand', help="Set the desired endpoint frame by its name; otherwise, it is right_hand frame by default") parser.add_argument( "-f", "--force_command", type=float, nargs='+', default=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], help="A list of desired force commands, one for each of the 6 directions -- in force control mode this is the vector of desired forces/torques to be regulated in (N) and (Nm), in impedance with force limit mode this vector specifies the magnitude of forces/torques (N and Nm) that the command will not exceed") parser.add_argument( "-kn", "--K_nullspace", type=float, nargs='+', default=[5.0, 10.0, 5.0, 10.0, 5.0, 10.0, 5.0], help="A list of desired nullspace stiffnesses, one for each of the 7 joints (a single value can be provided to apply the same value to all the directions) -- units are in (Nm/rad)") parser.add_argument( "-dd", "--disable_damping_in_force_control", action='store_true', default=False, help="Disable damping in force control") parser.add_argument( "-dr", "--disable_reference_resetting", action='store_true', default=False, help="The reference signal is reset to actual position to avoid jerks/jumps when interaction parameters are changed. This option allows the user to disable this feature.") parser.add_argument( "-rc", "--rotations_for_constrained_zeroG", action='store_true', default=False, help="Allow arbitrary rotational displacements from the current orientation for constrained zero-G (use only for a stationary reference orientation)") parser.add_argument( "--timeout", type=float, default=None, help="Max time in seconds to complete motion goal before returning. None is interpreted as an infinite timeout.") args = parser.parse_args(rospy.myargv()[1:]) try: rospy.init_node('path_planner_py') limb = Limb() traj = MotionTrajectory(limb = limb) wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=args.speed_ratio, max_joint_accel=args.accel_ratio) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) # joint_angles = limb.joint_ordered_angles() # waypoint.set_joint_angles(joint_angles = joint_angles) # traj.append_waypoint(waypoint.to_msg()) # joint = ik_service_client(poses).values()[::-1] # joint angles from J0 to J6 # if len(joint_angles) != len(joint_angles): # rospy.logerr('The number of joint_angles must be %d', len(joint_angles)) # return None # # waypoint.set_joint_angles(joint_angles = args.joint_angles) # waypoint.set_joint_angles(joint_angles = joint) #####divide the whole path into three parts: soft begin, uniform motion, soft stop#### final_pos = args.position # get endpoint state endpoint_state = limb.tip_state('right_hand') current_pos = endpoint_state.pose.position dis = [final_pos[0]-current_pos.x, final_pos[1]-current_pos.y, final_pos[2]-current_pos.z] uniform_motion = [current_pos.x + dis[0]/5, current_pos.y + dis[1]/5, current_pos.z + dis[2]/5] soft_stop = [current_pos.x + 4*dis[0]/5, current_pos.y + 4*dis[1]/5, current_pos.z + 4*dis[2]/5] ####################################################################################### # waypoint = path_planning(uniform_motion, args.orientation, 0.25, 0.01) # traj.append_waypoint(waypoint.to_msg()) # waypoint = path_planning(soft_stop, args.orientation, 0.25, 0) # traj.append_waypoint(waypoint.to_msg()) # waypoint = path_planning(final_pos, args.orientation, 0.25, 0.01) # # joint = path_planning(uniform_motion, args.orientation, 0.2, 0.1) # joint angles from J0 to J6 # # waypoint.set_joint_angles(joint_angles = joint) # # traj.append_waypoint(waypoint.to_msg()) # # joint = path_planning(soft_stop, args.orientation, 0.2, 0.1) # joint angles from J0 to J6 # # waypoint.set_joint_angles(joint_angles = joint) # # traj.append_waypoint(waypoint.to_msg()) # # joint = path_planning(final_pos, args.orientation, 0.2, 0.1) # joint angles from J0 to J6 # # waypoint.set_joint_angles(joint_angles = joint) # traj.append_waypoint(waypoint.to_msg()) ###########open traj file filename = 'traj' with open(filename, 'r') as f: lines = f.readlines() l = len(lines) - 1 wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=0.5, max_joint_accel=0.01) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) for line in lines[1:int(floor(2*l/5))]: print(line) jnt_angles = [float(x) for x in line.rstrip().split(',')[1:8]] waypoint.set_joint_angles(joint_angles = jnt_angles) traj.append_waypoint(waypoint.to_msg()) wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=0.5, max_joint_accel=0) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) for line in lines[int(floor(2*l/5)):int(floor(3*l/5))]: print(line) jnt_angles = [float(x) for x in line.rstrip().split(',')[1:8]] waypoint.set_joint_angles(joint_angles = jnt_angles) traj.append_waypoint(waypoint.to_msg()) wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=0.5, max_joint_accel=0.01) waypoint = MotionWaypoint(options = wpt_opts.to_msg(), limb = limb) for line in lines[int(floor(3*l/5)):]: print(line) jnt_angles = [float(x) for x in line.rstrip().split(',')[1:8]] waypoint.set_joint_angles(joint_angles = jnt_angles) traj.append_waypoint(waypoint.to_msg()) # set the interaction control options in the current configuration interaction_options = InteractionOptions() trajectory_options = TrajectoryOptions() trajectory_options.interaction_control = True trajectory_options.interpolation_type = args.trajType interaction_options.set_interaction_control_active(int2bool(args.interaction_active)) interaction_options.set_K_impedance(args.K_impedance) interaction_options.set_max_impedance(int2bool(args.max_impedance)) interaction_options.set_interaction_control_mode(args.interaction_control_mode) interaction_options.set_in_endpoint_frame(int2bool(args.in_endpoint_frame)) interaction_options.set_force_command(args.force_command) interaction_options.set_K_nullspace(args.K_nullspace) interaction_options.set_endpoint_name(args.endpoint_name) if len(args.interaction_frame) < 7: rospy.logerr('The number of elements must be 7!') elif len(args.interaction_frame) == 7: quat_sum_square = args.interaction_frame[3]*args.interaction_frame[3] + args.interaction_frame[4]*args.interaction_frame[4] + args.interaction_frame[5]*args.interaction_frame[5] + args.interaction_frame[6]*args.interaction_frame[6] if quat_sum_square < 1.0 + 1e-7 and quat_sum_square > 1.0 - 1e-7: interaction_frame = Pose() interaction_frame.position.x = args.interaction_frame[0] interaction_frame.position.y = args.interaction_frame[1] interaction_frame.position.z = args.interaction_frame[2] interaction_frame.orientation.w = args.interaction_frame[3] interaction_frame.orientation.x = args.interaction_frame[4] interaction_frame.orientation.y = args.interaction_frame[5] interaction_frame.orientation.z = args.interaction_frame[6] interaction_options.set_interaction_frame(interaction_frame) else: rospy.logerr('Invalid input to quaternion! The quaternion must be a unit quaternion!') else: rospy.logerr('Invalid input to interaction_frame!') interaction_options.set_disable_damping_in_force_control(args.disable_damping_in_force_control) interaction_options.set_disable_reference_resetting(args.disable_reference_resetting) interaction_options.set_rotations_for_constrained_zeroG(args.rotations_for_constrained_zeroG) trajectory_options.interaction_params = interaction_options.to_msg() traj.set_trajectory_options(trajectory_options) result = traj.send_trajectory(timeout=args.timeout) if result is None: rospy.logerr('Trajectory FAILED to send!') return if result.result: rospy.loginfo('Motion controller successfully finished the trajectory with interaction options set!') else: rospy.logerr('Motion controller failed to complete the trajectory with error %s', result.errorId) # print the resultant interaction options rospy.loginfo('Interaction Options:\n%s', interaction_options.to_msg()) except rospy.ROSInterruptException: rospy.logerr('Keyboard interrupt detected from the user. %s', 'Exiting before trajectory completion.')
def run(self): rate = rospy.Rate(100) limb = Limb() traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.CARTESIAN traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=0.5, max_joint_accel=0.5, corner_distance=0.05) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) self.pose.header = Header(stamp=rospy.Time.now(), frame_id='base') self.pose.pose.position.x = 0.0 self.pose.pose.position.y = -0.6 self.pose.pose.position.z = 0.5 self.pose.pose.orientation.x = 0.5 self.pose.pose.orientation.y = -0.5 self.pose.pose.orientation.z = 0.5 self.pose.pose.orientation.w = 0.5 joint_angles = limb.joint_ordered_angles() waypoint.set_cartesian_pose(self.pose, "right_hand", joint_angles) self.waypoints.append(waypoint) rospy.loginfo("Sending inital waypoint: %s", self.waypoints[0].to_string()) traj.append_waypoint(self.waypoints[0].to_msg()) result = traj.send_trajectory() if result is None: rospy.logerr('Trajectory FAILED to send') elif result.result: rospy.loginfo( 'Motion controller successfully finished the trajectory!') else: rospy.logerr( 'Motion controller failed to complete the trajectory with error %s', result.errorId) traj.clear_waypoints() l = Lights() l_name = 'head_green_light' initial_state = l.get_light_state(l_name) for i in range(0, 2): state = not initial_state l.set_light_state(l_name, state) rospy.sleep(0.5) state = not state l.set_light_state(l_name, state) rospy.sleep(0.5) l.set_light_state(l_name, True) for i in range(0, 19): self.gen_rand_waypoint() sendCommand = True while not rospy.is_shutdown(): traj.clear_waypoints() for i in range(0, 19): self.waypoints.pop(i) self.gen_rand_waypoint() for point in self.waypoints: traj.append_waypoint(point.to_msg()) print(len(self.waypoints)) result = traj.send_trajectory(wait_for_result=True) self.firstShutdown = True def clean_shutdown(): if self.firstShutdown: print("STOPPING TRAJECTORY") traj.stop_trajectory() traj.clear_waypoints() l = Lights() l.set_light_state('head_green_light', False) self.firstShutdown = False rospy.on_shutdown(clean_shutdown) rate.sleep() return
def move(self, point_list = None, wait = True, MAX_SPD_RATIO=0.4, MAX_JOINT_ACCL=[7.0, 5.0, 8.0, 8.0, 8.0, 8.0, 8.0]): # one point in point_list = [x_coord, y_coord, z_coord, x_deg, y_deg, z_deg] try: limb = Limb() # point_list = [pointA, pointB, pointC, ...] traj_options = TrajectoryOptions() traj_options.interpolation_type = TrajectoryOptions.JOINT traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) if self.STOP: traj.stop_trajectory() return True wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=MAX_SPD_RATIO, max_joint_accel=MAX_JOINT_ACCL) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) angles = limb.joint_ordered_angles() waypoint.set_joint_angles(joint_angles=angles) traj.append_waypoint(waypoint.to_msg()) for point in point_list: #q_base = quaternion_from_euler(0, math.pi/2, 0) q_base = quaternion_from_euler(0, 0, 0) #q_rot = quaternion_from_euler(math.radians(point[3]), math.radians(point[4]), math.radians(point[5])) # USE THIS IF ANGLES ARE IN DEGREES q_rot = quaternion_from_euler(point[3], point[4], point[5]) # USE THIS IF ANGLES ARE IN RADIANS q = quaternion_multiply(q_rot, q_base) # DEFINE ORIGIN origin = { 'x' : 0.65, 'y' : 0.0, 'z' : 0.4 } # CREATE CARTESIAN POSE FOR IK REQUEST newPose = PoseStamped() newPose.header = Header(stamp=rospy.Time.now(), frame_id='base') newPose.pose.position.x = point[0] + origin['x'] newPose.pose.position.y = point[1] + origin['y'] newPose.pose.position.z = point[2] + origin['z'] newPose.pose.orientation.x = q[0] newPose.pose.orientation.y = q[1] newPose.pose.orientation.z = q[2] newPose.pose.orientation.w = q[3] # REQUEST IK SERVICE FROM ROS ns = "ExternalTools/right/PositionKinematicsNode/IKService" iksvc = rospy.ServiceProxy(ns, SolvePositionIK) ikreq = SolvePositionIKRequest() # SET THE NEW POSE AS THE IK REQUEST ikreq.pose_stamp.append(newPose) ikreq.tip_names.append('right_hand') # ATTEMPT TO CALL THE SERVICE try: rospy.wait_for_service(ns, 5.0) resp = iksvc(ikreq) except: print("IK SERVICE CALL FAILED") return # HANDLE RETURN if (resp.result_type[0] > 0): joint_angles = resp.joints[0].position # APPEND JOINT ANGLES TO NEW WAYPOINT waypoint.set_joint_angles(joint_angles=joint_angles) traj.append_waypoint(waypoint.to_msg()) else: print("INVALID POSE") print(resp.result_type[0]) if(wait): print(" \n --- Sending trajectory and waiting for finish --- \n") result = traj.send_trajectory(wait_for_result=wait) if result is None: rospy.logerr('Trajectory FAILED to send') success = False elif result.result: rospy.loginfo('Motion controller successfully finished the trajcetory') success = True else: rospy.logerr('Motion controller failed to complete the trajectory. Error: %s', result.errorId) success = False else: print("\n --- Sending trajector w/out waiting --- \n") traj.send_trajectory(wait_for_result=wait) success = True return success except rospy.ROSInterruptException: print("User interrupt detected. Exiting before trajectory completes")