def joint_angles(args): # arg_fmt = argparse.RawDescriptionHelpFormatter # parser = argparse.ArgumentParser(formatter_class=arg_fmt, # description=main.__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.5, # 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( # "--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_joint_angles_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()) 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!') return True 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 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 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 go_to_angles(joint_angles_goal, speed_ratio_goal, accel_ratio_goal, timeout_goal): try: #rospy.init_node('go_to_joint_angles_py') # initialze once limb = Limb() traj = MotionTrajectory(limb=limb) wpt_opts = MotionWaypointOptions( max_joint_speed_ratio=speed_ratio_goal, max_joint_accel=accel_ratio_goal) 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(joint_angles_goal) != len(joint_angles): rospy.logerr('The number of joint_angles must be %d', len(joint_angles)) return None waypoint.set_joint_angles(joint_angles=joint_angles_goal) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=timeout_goal) 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 gen_rand_waypoint(self): newX = (random.random() / 5) - 0.1 newY = (random.random() / 5) - 0.7 newZ = (random.random() / 5) + 0.4 newPose = PoseStamped() newPose.header = Header(stamp=rospy.Time.now(), frame_id='base') newPose.pose.position.x = newX newPose.pose.position.y = newY newPose.pose.position.z = newZ newPose.pose.orientation.x = 0.5 newPose.pose.orientation.y = -0.5 newPose.pose.orientation.z = 0.5 newPose.pose.orientation.w = 0.5 limb = Limb() wpt_opts = MotionWaypointOptions(max_joint_speed_ratio=1.0, max_joint_accel=1.0, corner_distance=0.05) waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) waypoint.set_cartesian_pose(newPose, "right_hand", limb.joint_ordered_angles()) self.waypoints.append(waypoint)
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(): """ Move the robot arm to the specified configuration. Call using: $ rosrun intera_examples go_to_joint_angles.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 [...] with a speed ratio of 0.9 and an accel ratio of 0.1 """ arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__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.5, 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( "--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('go_to_joint_angles_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()) 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 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 """ arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__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." ) 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() 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 if not args.joint_angles: # using current joint angles for nullspace bais if not provided joint_angles = limb.joint_ordered_angles() waypoint.set_cartesian_pose(poseStamped, args.tip_name, joint_angles) else: 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 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.')
class Breath(object): 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 callback_update_breath1(self,msg): self.robot_state = msg.data if self.robot_state != 0: self.traj.stop_trajectory() def callback_update_breath2(self,msg): self.breath_state = msg.data if not self.breath_state: self.traj.stop_trajectory() def run(self): rate = rospy.Rate(10) while not rospy.is_shutdown(): if self.breath_state and self.robot_state == 0: self.traj.send_trajectory(timeout=None) rate.sleep()
pose_goal = Pose() pose_goal.orientation.w = OR_W pose_goal.orientation.x = OR_X pose_goal.orientation.y = OR_Y pose_goal.orientation.z = OR_Z pose_goal.position.x = BASE_X pose_goal.position.y = BASE_Y pose_goal.position.z = BASE_Z poseStamped = PoseStamped() poseStamped.pose = pose_goal traj = MotionTrajectory(trajectory_options=traj_options, limb=limb) joint_angles = limb.joint_ordered_angles() waypoint = MotionWaypoint(options=wpt_opts.to_msg(), limb=limb) waypoint.set_cartesian_pose(poseStamped, 'right_hand', joint_angles) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=5.0) rate = rospy.Rate(30.0) # SUGGEST - Try 10 or more while not rospy.is_shutdown(): try: (trans, rot) = listener.lookupTransform('kinect/user_1/torso', 'kinect/user_1/right_hand', rospy.Time(0)) except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
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 main(): # if len(sys.argv) < 4: # print('{0} <BindIP><Server IP><Message>'.format(sys.argv[0])) # sys.exit() bindIP = '192.168.101.5' #sys.argv[1] serverIP = '192.168.101.12' #sys.argv[2] sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) # SOCK_STREAM은 TCP socket을 뜻함 sock.bind((bindIP, 0)) sock.connect((serverIP, 5425)) # 서버에 연결 요청 rospy.init_node('sawyer_client') arg_fmt = argparse.RawDescriptionHelpFormatter parser = argparse.ArgumentParser(formatter_class=arg_fmt, description=main.__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.5, 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( "--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:]) goal_joint_angles = [0.0, -0.0, 0.0, 0.0, 0.0, 0.0, 0.0] while True: # 서버로 부터 수신 rbuff = sock.recv(1024) # 메시지 수신 received = str(rbuff) # print('수신:{0}'.format(received)) if received.count >= 5: center_str = received.split('SM')[1].split('SE')[0] print(center_str) if center_str == 'Q': break elif center_str == 'A': goal_joint_angles = [0.0, -0.9, 0.0, 1.8, 0.0, -0.9, 0.0] elif center_str == 'B': goal_joint_angles = [0.0, -0.0, 0.0, 0.0, 0.0, 0.0, 0.0] 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()) waypoint.set_joint_angles(joint_angles = goal_joint_angles) traj.append_waypoint(waypoint.to_msg()) result = traj.send_trajectory(timeout=args.timeout) sock.close()
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 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")