31 Joint Trajectory Action Client Example 41 from control_msgs.msg
import (
42 FollowJointTrajectoryAction,
43 FollowJointTrajectoryGoal,
45 from trajectory_msgs.msg
import (
51 print(
"Initializing node... ")
52 rospy.init_node(
"joint_trajectory_client_example")
54 print(
"Running. Ctrl-c to quit")
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,
66 '/fullbody_controller/follow_joint_trajectory',
67 FollowJointTrajectoryAction,
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")
76 goal = FollowJointTrajectoryGoal()
77 goal.goal_time_tolerance = rospy.Time(1)
78 goal.trajectory.joint_names = positions.keys()
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)
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)
105 goal.trajectory.header.stamp = rospy.Time.now()
106 client.send_goal(goal)
109 if not client.wait_for_result(timeout=rospy.Duration(20)):
110 rospy.logerr(
"Timed out waiting for JTA")
111 rospy.loginfo(
"Exitting...")
114 if __name__ ==
"__main__":