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 Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import rospy
19 import moveit_commander
20 import math
21 from geometry_msgs.msg import Pose
22 from geometry_msgs.msg import Point
23 from geometry_msgs.msg import Quaternion
24 import rosnode
25 from tf.transformations import quaternion_from_euler
26 
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):
31  way_points = []
32  q = quaternion_from_euler( 0.0, math.radians(180), 0.0 )
33  target_orientation = Quaternion(q[0], q[1], q[2], q[3])
34 
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))
38  target_pose = Pose()
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)
44 
45  path, fraction = arm.compute_cartesian_path(way_points, eef_step, jump_threshold, avoid_collisions)
46  arm.execute(path)
47 
48 def main():
49  gripper.set_joint_value_target([0.9, 0.9])
50  gripper.go()
51 
52  arm.set_named_target("home")
53  arm.go()
54 
55  # 座標(x=0.3, y=0.0, z=0.1)を中心に、XY平面上に半径0.1 mの円を3回描くように手先を動かす
56  follow_circular_path(center_position=Point(0.3, 0.0, 0.1), radius=0.1, repeat=3)
57 
58  arm.set_named_target("vertical")
59  arm.go()
60 
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")
68 
69  try:
70  if not rospy.is_shutdown():
71  main()
72  except rospy.ROSInterruptException:
73  pass
cartesian_path_example.follow_circular_path
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)
Definition: cartesian_path_example.py:27
cartesian_path_example.main
def main()
Definition: cartesian_path_example.py:48


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Oct 2 2023 02:39:27