37 from rospy.rostime
import Duration
40 from actionlib_msgs.msg
import GoalStatus
41 import naoqi_bridge_msgs.msg
42 from naoqi_bridge_msgs.msg
import JointTrajectoryGoal, JointTrajectoryAction, BodyPoseAction, BodyPoseGoal
43 from trajectory_msgs.msg
import JointTrajectory, JointTrajectoryPoint
45 from sensor_msgs.msg
import JointState
46 from std_msgs.msg
import String
47 from std_msgs.msg
import Bool
48 from std_srvs.srv
import Empty
55 rospy.init_node(
'pose_manager')
63 if self.trajectoryClient.wait_for_server(rospy.Duration(3.0)):
65 rospy.wait_for_service(
"stop_walk_srv", timeout=2.0)
68 rospy.logwarn(
"stop_walk_srv not available, pose_manager will not stop the walker before executing a trajectory. " 69 +
"This is normal if there is no nao_walker running.")
71 self.poseServer.start()
73 rospy.loginfo(
"pose_manager running, offering poses: %s", self.poseLibrary.keys());
76 rospy.logfatal(
"Could not connect to required \"joint_trajectory\" action server, is the nao_controller node running?");
77 rospy.signal_shutdown(
"Required component missing");
82 poses = xapparser.getpostures(xaplibrary)
83 except RuntimeError
as re:
84 rospy.logwarn(
"Error while parsing the XAP file: %s" % str(re))
87 for name, pose
in poses.items():
89 trajectory = JointTrajectory()
91 trajectory.joint_names = pose.keys()
92 joint_values = pose.values()
94 point = JointTrajectoryPoint()
95 point.time_from_start = Duration(2.0)
96 point.positions = pose.values()
97 trajectory.points = [point]
104 xaplibrary = rospy.get_param(
'~xap',
None)
108 poses = rospy.get_param(
'~poses',
None)
110 for key,value
in poses.iteritems():
113 trajectory = JointTrajectory()
114 trajectory.joint_names = value[
"joint_names"]
115 point = JointTrajectoryPoint()
116 point.time_from_start = Duration(value[
"time_from_start"])
117 point.positions = value[
"positions"]
118 trajectory.points = [point]
121 rospy.logwarn(
"Could not parse pose \"%s\" from the param server:", key);
122 rospy.logwarn(sys.exc_info())
126 trajectory = JointTrajectory()
127 trajectory.joint_names = [
"Body"]
128 point = JointTrajectoryPoint()
129 point.time_from_start = Duration(1.5)
130 point.positions = [0.0,0.0,
131 1.545, 0.33, -1.57, -0.486, 0.0, 0.0,
132 -0.3, 0.057, -0.744, 2.192, -1.122, -0.035,
133 -0.3, 0.057, -0.744, 2.192, -1.122, -0.035,
134 1.545, -0.33, 1.57, 0.486, 0.0, 0.0]
135 trajectory.points = [point]
139 rospy.loginfo(
"Loaded %d poses: %s", len(self.
poseLibrary), self.poseLibrary.keys())
144 rospy.loginfo(
"Pose %s not in library, reload library from parameters..." % goal.pose_name)
148 rospy.loginfo(
"Executing body pose %s...", goal.pose_name);
152 trajGoal = JointTrajectoryGoal()
154 trajGoal.trajectory = self.
poseLibrary[goal.pose_name]
155 timeout = trajGoal.trajectory.points[-1].time_from_start + Duration(1.0)
156 trajGoal.trajectory.header.stamp = rospy.Time.now()
158 self.trajectoryClient.send_goal_and_wait(trajGoal, timeout)
159 if self.trajectoryClient.get_state() != GoalStatus.SUCCEEDED:
160 self.poseServer.set_aborted(text=
"JointTrajectory action did not succeed (timeout?)");
162 self.poseServer.set_succeeded()
163 rospy.loginfo(
"Done.");
166 msg =
"pose \""+goal.pose_name+
"\" not in pose_manager's library";
167 rospy.logwarn(
"%s", msg)
168 self.poseServer.set_aborted(text=str(msg));
172 if __name__ ==
'__main__':
def parseXapPoses(self, xaplibrary)
def executeBodyPose(self, goal)