11 import moveit_commander
13 from geometry_msgs.msg
import Pose
14 from geometry_msgs.msg
import Point
15 from geometry_msgs.msg
import Quaternion
17 from tf.transformations
import quaternion_from_euler
20 center_position=Point(0.3, 0.0, 0.1), radius=0.1,
21 num_of_waypoints=30, repeat=1,
22 eef_step=0.01, jump_threshold=0.0, avoid_collisions=
True):
24 q = quaternion_from_euler( 0.0, math.radians(180), 0.0 )
25 target_orientation = Quaternion(q[0], q[1], q[2], q[3])
27 for r
in range(repeat):
28 for i
in range(num_of_waypoints):
29 theta = 2.0 * math.pi * (i / float(num_of_waypoints))
31 target_pose.position.x = center_position.x + radius * math.cos(theta)
32 target_pose.position.y = center_position.y + radius * math.sin(theta)
33 target_pose.position.z = center_position.z
34 target_pose.orientation = target_orientation
35 way_points.append(target_pose)
37 path, fraction = arm.compute_cartesian_path(way_points, eef_step, jump_threshold, avoid_collisions)
41 gripper.set_joint_value_target([0.9, 0.9])
44 arm.set_named_target(
"home")
50 arm.set_named_target(
"vertical")
53 if __name__ ==
'__main__':
54 rospy.init_node(
"cartesian_path_example")
55 robot = moveit_commander.RobotCommander()
56 arm = moveit_commander.MoveGroupCommander(
"arm")
57 arm.set_max_velocity_scaling_factor(0.1)
58 arm.set_max_acceleration_scaling_factor(1.0)
59 gripper = moveit_commander.MoveGroupCommander(
"gripper")
62 if not rospy.is_shutdown():
64 except rospy.ROSInterruptException:
def follow_circular_path(center_position=Point(0.3, 0.0, 0.1), radius=0.1, num_of_waypoints=30, repeat=1, eef_step=0.01, jump_threshold=0.0, avoid_collisions=True)