19 import moveit_commander
21 from geometry_msgs.msg
import Pose
22 from geometry_msgs.msg
import Point
23 from geometry_msgs.msg
import Quaternion
25 from tf.transformations
import quaternion_from_euler
28 center_position=Point(0.3, 0.0, 0.1), radius=0.1,
29 num_of_waypoints=30, repeat=1,
30 eef_step=0.01, jump_threshold=0.0, avoid_collisions=
True):
32 q = quaternion_from_euler( 0.0, math.radians(180), 0.0 )
33 target_orientation = Quaternion(q[0], q[1], q[2], q[3])
35 for r
in range(repeat):
36 for i
in range(num_of_waypoints):
37 theta = 2.0 * math.pi * (i / float(num_of_waypoints))
39 target_pose.position.x = center_position.x + radius * math.cos(theta)
40 target_pose.position.y = center_position.y + radius * math.sin(theta)
41 target_pose.position.z = center_position.z
42 target_pose.orientation = target_orientation
43 way_points.append(target_pose)
45 path, fraction = arm.compute_cartesian_path(way_points, eef_step, jump_threshold, avoid_collisions)
49 gripper.set_joint_value_target([0.9, 0.9])
52 arm.set_named_target(
"home")
58 arm.set_named_target(
"vertical")
61 if __name__ ==
'__main__':
62 rospy.init_node(
"cartesian_path_example")
63 robot = moveit_commander.RobotCommander()
64 arm = moveit_commander.MoveGroupCommander(
"arm")
65 arm.set_max_velocity_scaling_factor(0.1)
66 arm.set_max_acceleration_scaling_factor(1.0)
67 gripper = moveit_commander.MoveGroupCommander(
"gripper")
70 if not rospy.is_shutdown():
72 except rospy.ROSInterruptException: