joint_trajectory_client_example.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2016, 2019 Kei Okada
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # 1. Redistributions of source code must retain the above copyright notice,
10 # this list of conditions and the following disclaimer.
11 # 2. Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # 3. Neither the name of the Rethink Robotics nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 """
31 Joint Trajectory Action Client Example
32 """
33 
34 import rospy
35 
36 import actionlib
37 
38 import sys
39 import time
40 
41 from control_msgs.msg import (
42  FollowJointTrajectoryAction,
43  FollowJointTrajectoryGoal,
44 )
45 from trajectory_msgs.msg import (
46  JointTrajectoryPoint,
47 )
48 
49 
50 def main():
51  print("Initializing node... ")
52  rospy.init_node("joint_trajectory_client_example")
53  rospy.sleep(1)
54  print("Running. Ctrl-c to quit")
55  positions = {
56  'head_neck_p': 0.0, 'head_neck_y': 0.2,
57  'larm_shoulder_p': 0.1, 'larm_shoulder_r': 0.3, 'larm_shoulder_y': -0.1, 'larm_elbow_p': -0.2, 'larm_elbow_p2': -0.2,
58  'larm_wrist_r': 0, 'larm_wrist_y': 0, 'larm_gripper': 1.1,
59  'rarm_shoulder_p': 0.1, 'rarm_shoulder_r': -0.3, 'rarm_shoulder_y': 0.1, 'rarm_elbow_p': -0.2, 'rarm_elbow_p2': -0.2,
60  'rarm_wrist_r': 0, 'rarm_wrist_y': 0, 'rarm_gripper': 1.1,
61  'torso_waist_p': -0.05, 'torso_waist_y': 0.0, 'torso_rthrust_p': 0.0, 'torso_rthrust_r': 0.0, 'torso_lthrust_p': 0.0, 'torso_lthrust_r': 0.0,
62  'lleg_crotch_p': -0.35, 'lleg_crotch_r': 0.2, 'lleg_crotch_y': 0.35, 'lleg_knee_p': 0.20, 'lleg_knee_p2': 0.20, 'lleg_ankle_p': 0.05, 'lleg_ankle_r': -0.05,
63  'rleg_crotch_p': 0.20, 'rleg_crotch_r': -0.1, 'rleg_crotch_y': -0.15, 'rleg_knee_p': 0.05, 'rleg_knee_p2': 0.05, 'rleg_ankle_p': -0.2, 'rleg_ankle_r': 0.1,
64  }
66  '/fullbody_controller/follow_joint_trajectory',
67  FollowJointTrajectoryAction,
68  )
69 
70  if not client.wait_for_server(timeout=rospy.Duration(10)):
71  rospy.logerr("Timed out waiting for Action Server")
72  rospy.signal_shutdown("Timed out waiting for Action Server")
73  sys.exit(1)
74 
75  # init goal
76  goal = FollowJointTrajectoryGoal()
77  goal.goal_time_tolerance = rospy.Time(1)
78  goal.trajectory.joint_names = positions.keys()
79 
80  # points
81  point = JointTrajectoryPoint()
82  goal.trajectory.joint_names = positions.keys()
83  point.positions = positions.values()
84  point.time_from_start = rospy.Duration(10)
85  goal.trajectory.points.append(point)
86 
87  point = JointTrajectoryPoint()
88  positions['torso_waist_p'] += 0.2
89  positions['torso_waist_y'] += 0.2
90  positions['head_neck_p'] = 0.05
91  positions['head_neck_y'] = 0.15
92  positions['lleg_crotch_p'] += -0.1
93  positions['rleg_crotch_p'] += -0.1
94  positions['rarm_shoulder_p'] += 0.2
95  positions['larm_shoulder_p'] += 0.2
96  positions['rarm_elbow_p'] += -0.2
97  positions['rarm_elbow_p2'] += -0.2
98  positions['larm_elbow_p'] += -0.2
99  positions['larm_elbow_p2'] += -0.2
100  point.positions = positions.values()
101  point.time_from_start = rospy.Duration(12)
102  goal.trajectory.points.append(point)
103 
104  # send goal
105  goal.trajectory.header.stamp = rospy.Time.now()
106  client.send_goal(goal)
107  print(goal)
108  print("waiting...")
109  if not client.wait_for_result(timeout=rospy.Duration(20)):
110  rospy.logerr("Timed out waiting for JTA")
111  rospy.loginfo("Exitting...")
112 
113 
114 if __name__ == "__main__":
115  main()


gundam_rx78_control
Author(s): Kei Okada , Naoki Hiraoka
autogenerated on Wed Sep 2 2020 03:33:33