test_hironx_ros_bridge.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Software License Agreement (BSD License)
5 #
6 # Copyright (c) 2014, JSK Lab, University of Tokyo
7 # Copyright (c) 2014, TORK
8 # All rights reserved.
9 #
10 # Redistribution and use in source and binary forms, with or without
11 # modification, are permitted provided that the following conditions
12 # are met:
13 #
14 # * Redistributions of source code must retain the above copyright
15 # notice, this list of conditions and the following disclaimer.
16 # * Redistributions in binary form must reproduce the above
17 # copyright notice, this list of conditions and the following
18 # disclaimer in the documentation and/or other materials provided
19 # with the distribution.
20 # * Neither the name of JSK Lab, University of Tokyo, TORK, nor the
21 # names of its contributors may be used to endorse or promote products
22 # derived from this software without specific prior written permission.
23 #
24 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 # POSSIBILITY OF SUCH DAMAGE.
36 
37 # 20170403 ***DO NOT*** refer to this file from any testcases. Instead, use
38 # https://github.com/start-jsk/rtmros_hironx/blob/indigo-devel/hironx_ros_bridge/src/hironx_ros_bridge/testutil/test_hironx_ros_bridge.py
39 # which this file is a mere duplicate of at the time of writing. See
40 # https://github.com/start-jsk/rtmros_hironx/pull/490 and relevant
41 # tickets/PRs for further info.
42 
43 PKG = 'hironx_ros_bridge'
44 # rosbuild needs load_manifest
45 try:
46  import roslib
47  import hironx_ros_bridge
48 except:
49  import roslib; roslib.load_manifest(PKG)
50  import hironx_ros_bridge
51 
52 from hironx_ros_bridge import hironx_client as hironx
53 import rospy, actionlib, math, numpy
54 import tf
55 from tf.transformations import quaternion_matrix, euler_from_matrix
56 
57 import unittest
58 
59 # for catkin compiled environment, pr2_controller_msgs is not catkinized
60 roslib.load_manifest('pr2_controllers_msgs')
61 import pr2_controllers_msgs.msg
62 import trajectory_msgs.msg
63 
64 from sensor_msgs.msg import JointState
65 from pr2_controllers_msgs.msg import JointTrajectoryAction
66 from trajectory_msgs.msg import JointTrajectoryPoint
67 from hrpsys_ros_bridge.srv import *
68 
69 import time
70 import tempfile
71 
72 class TestHiroROSBridge(unittest.TestCase):
73 
74  def joint_states_cb(self, msg):
75  self.joint_states.append(msg)
76  self.joint_states = self.joint_states[0:3000]
77 
78  def __init__(self, *args, **kwargs):
79  super(TestHiroROSBridge, self).__init__(*args, **kwargs)
80  #
81  self.joint_states = []
82  rospy.init_node('hironx_ros_bridge_test')
83  self.joint_states_sub = rospy.Subscriber("joint_states", JointState, self.joint_states_cb)
84  self.filename_base = tempfile.mkstemp()[1]
85  self.filenames = []
86 
87  @classmethod
88  def setUpClass(self):
89  self.robot = hironx.HIRONX()
90  self.robot.init()
91 
93 
94  self.larm = actionlib.SimpleActionClient("/larm_controller/joint_trajectory_action", JointTrajectoryAction)
95  self.rarm = actionlib.SimpleActionClient("/rarm_controller/joint_trajectory_action", JointTrajectoryAction)
96  self.torso = actionlib.SimpleActionClient("/torso_controller/joint_trajectory_action", JointTrajectoryAction)
97  self.head = actionlib.SimpleActionClient("/head_controller/joint_trajectory_action", JointTrajectoryAction)
98  self.larm.wait_for_server()
99  self.rarm.wait_for_server()
100  self.torso.wait_for_server()
101  self.head.wait_for_server()
102 
103  rospy.wait_for_service('/SequencePlayerServiceROSBridge/setTargetPose')
104  self.set_target_pose = rospy.ServiceProxy('/SequencePlayerServiceROSBridge/setTargetPose', OpenHRP_SequencePlayerService_setTargetPose)
105  rospy.wait_for_service('/SequencePlayerServiceROSBridge/waitInterpolationOfGroup')
106  self.wait_interpolation_of_group = rospy.ServiceProxy('/SequencePlayerServiceROSBridge/waitInterpolationOfGroup', OpenHRP_SequencePlayerService_waitInterpolationOfGroup)
107 
108 
109  def tearDown(self):
110  self.reset_Pose()
111  True
112 
113  def setUp(self):
114  self.reset_Pose()
115 
116  def reset_Pose(self):
117  larm_goal = self.goal_LArm()
118  larm_goal = self.setup_Positions(larm_goal, [[ 0.0, -40.0, -90.0, 0.0, 0.0, 0.0]])
119  rarm_goal = self.goal_RArm()
120  rarm_goal = self.setup_Positions(rarm_goal, [[ 0.0, -40.0, -90.0, 0.0, 0.0, 0.0]])
121  head_goal = self.goal_Head()
122  head_goal = self.setup_Positions(head_goal, [[0, 20]])
123  torso_goal = self.goal_Torso()
124  torso_goal = self.setup_Positions(torso_goal, [[0]])
125  self.larm.send_goal(larm_goal)
126  self.rarm.send_goal(rarm_goal)
127  self.head.send_goal(head_goal)
128  self.torso.send_goal(torso_goal)
129  self.larm.wait_for_result()
130  self.rarm.wait_for_result()
131  self.head.wait_for_result()
132  self.torso.wait_for_result()
133 
134  def goal_LArm(self):
135  goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
136  goal.trajectory.joint_names.append("LARM_JOINT0")
137  goal.trajectory.joint_names.append("LARM_JOINT1")
138  goal.trajectory.joint_names.append("LARM_JOINT2")
139  goal.trajectory.joint_names.append("LARM_JOINT3")
140  goal.trajectory.joint_names.append("LARM_JOINT4")
141  goal.trajectory.joint_names.append("LARM_JOINT5")
142  return goal
143 
144  def goal_RArm(self):
145  goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
146  goal.trajectory.joint_names.append("RARM_JOINT0")
147  goal.trajectory.joint_names.append("RARM_JOINT1")
148  goal.trajectory.joint_names.append("RARM_JOINT2")
149  goal.trajectory.joint_names.append("RARM_JOINT3")
150  goal.trajectory.joint_names.append("RARM_JOINT4")
151  goal.trajectory.joint_names.append("RARM_JOINT5")
152  return goal
153 
154  def goal_Torso(self):
155  goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
156  goal.trajectory.joint_names.append("CHEST_JOINT0")
157  return goal
158 
159  def goal_Head(self):
160  goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
161  goal.trajectory.joint_names.append("HEAD_JOINT0")
162  goal.trajectory.joint_names.append("HEAD_JOINT1")
163  return goal
164 
165  def setup_Positions(self, goal, positions, tm = 1.0):
166  for p in positions:
167  point = trajectory_msgs.msg.JointTrajectoryPoint()
168  point.positions = [ x * math.pi / 180.0 for x in p]
169  point.time_from_start = rospy.Duration(tm)
170  goal.trajectory.points.append(point)
171  tm += tm
172  return goal
173 
174  def check_q_data(self, name):
175  import math
176  data = []
177 
178  name = name+".q"
179  f = open(name, 'w')
180  for j in self.joint_states:
181  current_time = j.header.stamp.to_sec();
182  current_value = [p*180/math.pi for p in j.position]
183  data.append([current_time, current_value[5]])
184  f.write(str(current_time)+' '+' '.join([str(i) for i in current_value])+"\n")
185  f.close()
186  self.filenames.append(name)
187  return data
188 
189  def write_output_to_pdf (self,name):
190  import os
191  cmd = "gnuplot -p -e \"set terminal pdf; set output '"+name+"'; plot "
192  for name in self.filenames:
193  cmd += "'"+name+"' using 0:7 title '"+name+"' with lines"
194  if name != self.filenames[-1]:
195  cmd += ","
196  cmd += "\""
197  os.system(cmd)
198  return cmd
199 
200 # unittest.main()
201 if __name__ == '__main__':
202  import rostest
203  rostest.rosrun(PKG, 'test_hronx_ros_bridge', TestHiroROSBridge)
204 
205 
206 
207 
def setup_Positions(self, goal, positions, tm=1.0)


hironx_ros_bridge
Author(s): Kei Okada , Isaac I.Y. Saito
autogenerated on Thu May 14 2020 03:52:05