sr_print_hand_joints_position.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright 2019 Shadow Robot Company Ltd.
3 #
4 # This program is free software: you can redistribute it and/or modify it
5 # under the terms of the GNU General Public License as published by the Free
6 # Software Foundation version 2 of the License.
7 #
8 # This program is distributed in the hope that it will be useful, but WITHOUT
9 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 # more details.
12 #
13 # You should have received a copy of the GNU General Public License along
14 # with this program. If not, see <http://www.gnu.org/licenses/>.
15 
16 # An example of how to print the current joint positions for all joints.
17 # Useful when used in conjunction with 'teach mode', as new motion sequences can
18 # be quickly produced from physically moving the robot into position and then
19 # recording those positions with this script. Angles can be printed in radians or degrees, an argument should be added
20 # when the script is called of either 'radians' or 'degrees', default is radians
21 
22 import rospy
23 from sr_robot_commander.sr_hand_commander import SrHandCommander
24 from sr_utilities.hand_finder import HandFinder
25 from numpy import arange
26 from math import pi
27 import argparse
28 
29 
30 rospy.init_node("print_hand_joints_position", anonymous=True)
31 
32 parser = argparse.ArgumentParser(description='A script to print hand joint positions. ',
33  add_help=True, usage='%(prog)s [-h] --angle_type ANGLE_TYPE',
34  formatter_class=argparse.RawTextHelpFormatter)
35 
36 parser.add_argument("--angle_type", default="radians", help="ANGLE_TYPE should be either degrees or radians")
37 args = parser.parse_args()
38 
39 angle_type = args.angle_type
40 
41 # Use the hand finder to get the hand prefix, to allow this script to be used with either left or right hands
42 hand_finder = HandFinder()
43 hand_parameters = hand_finder.get_hand_parameters()
44 
45 prefix = hand_parameters.mapping.values()
46 hand_serial = hand_parameters.mapping.keys()
47 scale = 1
48 
49 if angle_type == "degrees":
50  scale = 1 * (180/pi)
51 
52 for i in arange(0, len(prefix)):
53  hand_commander = SrHandCommander(hand_parameters=hand_parameters, hand_serial=hand_serial[i])
54 
55  print("Joints positions")
56 
57  all_joints_state = hand_commander.get_joints_position()
58 
59  hand_joints_state = {
60  k: (v * scale) for k, v in all_joints_state.items() if k.startswith(prefix[i] + "_")}
61 
62  print("Hand joints position \n " + str(hand_joints_state) + "\n")


sr_example
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 04:05:12