cartesian_path_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2020 RT Corporation
5 #
6 # Licensed under the RT Corporation NON-COMMERCIAL LICENSE.
7 # Please see https://github.com/rt-net/crane_x7_ros/blob/master/LICENSE
8 # for detail.
9 
10 import rospy
11 import moveit_commander
12 import math
13 from geometry_msgs.msg import Pose
14 from geometry_msgs.msg import Point
15 from geometry_msgs.msg import Quaternion
16 import rosnode
17 from tf.transformations import quaternion_from_euler
18 
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):
23  way_points = []
24  q = quaternion_from_euler( 0.0, math.radians(180), 0.0 )
25  target_orientation = Quaternion(q[0], q[1], q[2], q[3])
26 
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))
30  target_pose = Pose()
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)
36 
37  path, fraction = arm.compute_cartesian_path(way_points, eef_step, jump_threshold, avoid_collisions)
38  arm.execute(path)
39 
40 def main():
41  gripper.set_joint_value_target([0.9, 0.9])
42  gripper.go()
43 
44  arm.set_named_target("home")
45  arm.go()
46 
47  # 座標(x=0.3, y=0.0, z=0.1)を中心に、XY平面上に半径0.1 mの円を3回描くように手先を動かす
48  follow_circular_path(center_position=Point(0.3, 0.0, 0.1), radius=0.1, repeat=3)
49 
50  arm.set_named_target("vertical")
51  arm.go()
52 
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")
60 
61  try:
62  if not rospy.is_shutdown():
63  main()
64  except rospy.ROSInterruptException:
65  pass
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)


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Mar 1 2021 03:18:34