43 PKG =
'hironx_ros_bridge' 47 import hironx_ros_bridge
49 import roslib; roslib.load_manifest(PKG)
50 import hironx_ros_bridge
52 from hironx_ros_bridge
import hironx_client
as hironx
53 import rospy, actionlib, math, numpy
55 from tf.transformations
import quaternion_matrix, euler_from_matrix
60 roslib.load_manifest(
'pr2_controllers_msgs')
61 import pr2_controllers_msgs.msg
62 import trajectory_msgs.msg
64 from sensor_msgs.msg
import JointState
65 from pr2_controllers_msgs.msg
import JointTrajectoryAction
66 from trajectory_msgs.msg
import JointTrajectoryPoint
75 self.joint_states.append(msg)
79 super(TestHiroROSBridge, self).
__init__(*args, **kwargs)
82 rospy.init_node(
'hironx_ros_bridge_test')
98 self.larm.wait_for_server()
99 self.rarm.wait_for_server()
100 self.torso.wait_for_server()
101 self.head.wait_for_server()
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)
118 larm_goal = self.
setup_Positions(larm_goal, [[ 0.0, -40.0, -90.0, 0.0, 0.0, 0.0]])
120 rarm_goal = self.
setup_Positions(rarm_goal, [[ 0.0, -40.0, -90.0, 0.0, 0.0, 0.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()
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")
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")
155 goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
156 goal.trajectory.joint_names.append(
"CHEST_JOINT0")
160 goal = pr2_controllers_msgs.msg.JointTrajectoryGoal()
161 goal.trajectory.joint_names.append(
"HEAD_JOINT0")
162 goal.trajectory.joint_names.append(
"HEAD_JOINT1")
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)
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")
186 self.filenames.append(name)
191 cmd =
"gnuplot -p -e \"set terminal pdf; set output '"+name+
"'; plot " 193 cmd +=
"'"+name+
"' using 0:7 title '"+name+
"' with lines" 201 if __name__ ==
'__main__':
203 rostest.rosrun(PKG,
'test_hronx_ros_bridge', TestHiroROSBridge)
wait_interpolation_of_group
def __init__(self, args, kwargs)
def joint_states_cb(self, msg)
def check_q_data(self, name)
def write_output_to_pdf(self, name)
def setup_Positions(self, goal, positions, tm=1.0)